APM:Libraries
Compass_PerMotor.cpp
Go to the documentation of this file.
1 /*
2  per-motor compass compensation
3  */
4 
5 #include "AP_Compass.h"
6 #include <GCS_MAVLink/GCS.h>
7 
8 extern const AP_HAL::HAL &hal;
9 
11  // @Param: _EN
12  // @DisplayName: per-motor compass correction enable
13  // @Description: This enables per-motor compass corrections
14  // @Values: 0:Disabled,1:Enabled
15  // @User: Advanced
17 
18  // @Param: _EXP
19  // @DisplayName: per-motor exponential correction
20  // @Description: This is the exponential correction for the power output of the motor for per-motor compass correction
21  // @Range: 0 2
22  // @Increment: 0.01
23  // @User: Advanced
24  AP_GROUPINFO("_EXP", 2, Compass_PerMotor, expo, 0.65),
25 
26  // @Param: 1_X
27  // @DisplayName: Compass per-motor1 X
28  // @Description: Compensation for X axis of motor1
29  // @User: Advanced
30 
31  // @Param: 1_Y
32  // @DisplayName: Compass per-motor1 Y
33  // @Description: Compensation for Y axis of motor1
34  // @User: Advanced
35 
36  // @Param: 1_Z
37  // @DisplayName: Compass per-motor1 Z
38  // @Description: Compensation for Z axis of motor1
39  // @User: Advanced
40  AP_GROUPINFO("1", 3, Compass_PerMotor, compensation[0], 0),
41 
42  // @Param: 2_X
43  // @DisplayName: Compass per-motor2 X
44  // @Description: Compensation for X axis of motor2
45  // @User: Advanced
46 
47  // @Param: 2_Y
48  // @DisplayName: Compass per-motor2 Y
49  // @Description: Compensation for Y axis of motor2
50  // @User: Advanced
51 
52  // @Param: 2_Z
53  // @DisplayName: Compass per-motor2 Z
54  // @Description: Compensation for Z axis of motor2
55  // @User: Advanced
56  AP_GROUPINFO("2", 4, Compass_PerMotor, compensation[1], 0),
57 
58  // @Param: 3_X
59  // @DisplayName: Compass per-motor3 X
60  // @Description: Compensation for X axis of motor3
61  // @User: Advanced
62 
63  // @Param: 3_Y
64  // @DisplayName: Compass per-motor3 Y
65  // @Description: Compensation for Y axis of motor3
66  // @User: Advanced
67 
68  // @Param: 3_Z
69  // @DisplayName: Compass per-motor3 Z
70  // @Description: Compensation for Z axis of motor3
71  // @User: Advanced
72  AP_GROUPINFO("3", 5, Compass_PerMotor, compensation[2], 0),
73 
74  // @Param: 4_X
75  // @DisplayName: Compass per-motor4 X
76  // @Description: Compensation for X axis of motor4
77  // @User: Advanced
78 
79  // @Param: 4_Y
80  // @DisplayName: Compass per-motor4 Y
81  // @Description: Compensation for Y axis of motor4
82  // @User: Advanced
83 
84  // @Param: 4_Z
85  // @DisplayName: Compass per-motor4 Z
86  // @Description: Compensation for Z axis of motor4
87  // @User: Advanced
88  AP_GROUPINFO("4", 6, Compass_PerMotor, compensation[3], 0),
89 
91 };
92 
93 // constructor
95  compass(_compass)
96 {
98 }
99 
100 // return current scaled motor output
102 {
103  if (!have_motor_map) {
108  have_motor_map = true;
109  }
110  }
111  if (!have_motor_map) {
112  return 0;
113  }
114 
115  // this currently assumes first 4 channels.
116  uint16_t pwm = hal.rcout->read_last_sent(motor_map[motor]);
117 
118  // get 0 to 1 motor demand
119  float output = (hal.rcout->scale_esc_to_unity(pwm)+1) * 0.5;
120 
121  if (output <= 0) {
122  return 0;
123  }
124 
125  // scale for voltage
126  output *= voltage;
127 
128  // apply expo correction
129  output = powf(output, expo);
130  return output;
131 }
132 
133 // per-motor calibration update
135 {
136  for (uint8_t i=0; i<4; i++) {
137  field_sum[i].zero();
138  output_sum[i] = 0;
139  count[i] = 0;
140  start_ms[i] = 0;
141  }
142 
143  // we need to ensure we get current data by throwing away several
144  // samples. The offsets may have just changed from an offset
145  // calibration
146  for (uint8_t i=0; i<4; i++) {
147  compass.read();
148  hal.scheduler->delay(50);
149  }
150 
152  running = true;
153 }
154 
155 // per-motor calibration update
157 {
158  uint32_t now = AP_HAL::millis();
159 
160  // accumulate per-motor sums
161  for (uint8_t i=0; i<4; i++) {
162  float output = scaled_output(i);
163 
164  if (output <= 0) {
165  // motor is off
166  start_ms[i] = 0;
167  continue;
168  }
169  if (start_ms[i] == 0) {
170  start_ms[i] = now;
171  }
172  if (now - start_ms[i] < 500) {
173  // motor must run for 0.5s to settle
174  continue;
175  }
176 
177  // accumulate a sample
178  field_sum[i] += compass.get_field(0);
179  output_sum[i] += output;
180  count[i]++;
181  }
182 }
183 
184 // calculate per-motor calibration values
186 {
187  for (uint8_t i=0; i<4; i++) {
188  if (count[i] == 0) {
189  continue;
190  }
191 
192  // calculate effective output
193  float output = output_sum[i] / count[i];
194 
195  // calculate amount that field changed from base field
196  Vector3f field_change = base_field - (field_sum[i] / count[i]);
197  if (output <= 0) {
198  continue;
199  }
200 
201  Vector3f c = field_change / output;
202  compensation[i].set_and_save(c);
203  }
204 
205  // enable per-motor compensation
206  enable.set_and_save(1);
207 
208  running = false;
209 }
210 
211 /*
212  calculate total offset for per-motor compensation
213  */
215 {
216  offset.zero();
217 
218  if (running) {
219  // don't compensate while calibrating
220  return;
221  }
222 
223  for (uint8_t i=0; i<4; i++) {
224  float output = scaled_output(i);
225 
226  const Vector3f &c = compensation[i].get();
227 
228  offset += c * output;
229  }
230 }
Compass_PerMotor(Compass &_compass)
void calibration_end(void)
AP_Vector3f compensation[4]
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
Interface definition for the various Ground Control System.
void calibration_update(void)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
uint8_t motor_map[4]
virtual uint16_t read_last_sent(uint8_t ch)
Definition: RCOutput.h:74
bool read()
Definition: AP_Compass.cpp:979
static uint16_t pwm
Definition: RCOutput.cpp:20
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
virtual void delay(uint16_t ms)=0
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
these allow remapping of copter motors
Definition: SRV_Channel.h:77
float scaled_output(uint8_t motor)
uint32_t millis()
Definition: system.cpp:157
static Compass compass
Definition: AHRS_Test.cpp:20
void calibration_start(void)
uint32_t start_ms[4]
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
virtual float scale_esc_to_unity(uint16_t pwm)
Definition: RCOutput.h:121
void compensate(Vector3f &offset)
Vector3f field_sum[4]
#define AP_GROUPEND
Definition: AP_Param.h:121
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
static const struct AP_Param::GroupInfo var_info[]