APM:Copter
compassmot.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  compass/motor interference calibration
5  */
6 
7 // setup_compassmot - sets compass's motor interference parameters
8 MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
9 {
10 #if FRAME_CONFIG == HELI_FRAME
11  // compassmot not implemented for tradheli
12  return MAV_RESULT_UNSUPPORTED;
13 #else
14  int8_t comp_type; // throttle or current based compensation
15  Vector3f compass_base[COMPASS_MAX_INSTANCES]; // compass vector when throttle is zero
16  Vector3f motor_impact[COMPASS_MAX_INSTANCES]; // impact of motors on compass vector
17  Vector3f motor_impact_scaled[COMPASS_MAX_INSTANCES]; // impact of motors on compass vector scaled with throttle
18  Vector3f motor_compensation[COMPASS_MAX_INSTANCES]; // final compensation to be stored to eeprom
19  float throttle_pct; // throttle as a percentage 0.0 ~ 1.0
20  float throttle_pct_max = 0.0f; // maximum throttle reached (as a percentage 0~1.0)
21  float current_amps_max = 0.0f; // maximum current reached
22  float interference_pct[COMPASS_MAX_INSTANCES]; // interference as a percentage of total mag field (for reporting purposes only)
23  uint32_t last_run_time;
24  uint32_t last_send_time;
25  bool updated = false; // have we updated the compensation vector at least once
26  uint8_t command_ack_start = command_ack_counter;
27 
28  // exit immediately if we are already in compassmot
29  if (ap.compass_mot) {
30  // ignore restart messages
31  return MAV_RESULT_TEMPORARILY_REJECTED;
32  }else{
33  ap.compass_mot = true;
34  }
35 
36  // initialise output
37  for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
38  interference_pct[i] = 0.0f;
39  }
40 
41  GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
42 
43  // check compass is enabled
44  if (!g.compass_enabled) {
45  gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
46  ap.compass_mot = false;
47  return MAV_RESULT_TEMPORARILY_REJECTED;
48  }
49 
50  // check compass health
51  compass.read();
52  for (uint8_t i=0; i<compass.get_count(); i++) {
53  if (!compass.healthy(i)) {
54  gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Check compass");
55  ap.compass_mot = false;
56  return MAV_RESULT_TEMPORARILY_REJECTED;
57  }
58  }
59 
60  // check if radio is calibrated
61  if (!arming.rc_calibration_checks(true)) {
62  gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");
63  ap.compass_mot = false;
64  return MAV_RESULT_TEMPORARILY_REJECTED;
65  }
66 
67  // check throttle is at zero
68  read_radio();
69  if (channel_throttle->get_control_in() != 0) {
70  gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
71  ap.compass_mot = false;
72  return MAV_RESULT_TEMPORARILY_REJECTED;
73  }
74 
75  // check we are landed
76  if (!ap.land_complete) {
77  gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Not landed");
78  ap.compass_mot = false;
79  return MAV_RESULT_TEMPORARILY_REJECTED;
80  }
81 
82  // disable cpu failsafe
84 
85  // initialise compass
86  init_compass();
87 
88  // default compensation type to use current if possible
89  if (battery.has_current()) {
90  comp_type = AP_COMPASS_MOT_COMP_CURRENT;
91  }else{
92  comp_type = AP_COMPASS_MOT_COMP_THROTTLE;
93  }
94 
95  // send back initial ACK
96  mavlink_msg_command_ack_send(chan, MAV_CMD_PREFLIGHT_CALIBRATION,0);
97 
98  // flash leds
100 
101  // warn user we are starting calibration
102  gcs_chan.send_text(MAV_SEVERITY_INFO, "Starting calibration");
103 
104  // inform what type of compensation we are attempting
105  if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
106  gcs_chan.send_text(MAV_SEVERITY_INFO, "Current");
107  } else{
108  gcs_chan.send_text(MAV_SEVERITY_INFO, "Throttle");
109  }
110 
111  // disable throttle failsafe
113 
114  // disable motor compensation
116  for (uint8_t i=0; i<compass.get_count(); i++) {
118  }
119 
120  // get initial compass readings
121  last_run_time = millis();
122  while ( millis() - last_run_time < 500 ) {
124  }
125  compass.read();
126 
127  // store initial x,y,z compass values
128  // initialise interference percentage
129  for (uint8_t i=0; i<compass.get_count(); i++) {
130  compass_base[i] = compass.get_field(i);
131  interference_pct[i] = 0.0f;
132  }
133 
134  // enable motors and pass through throttle
135  init_rc_out();
137  motors->armed(true);
138 
139  // initialise run time
140  last_run_time = millis();
141  last_send_time = millis();
142 
143  // main run while there is no user input and the compass is healthy
144  while (command_ack_start == command_ack_counter && compass.healthy(compass.get_primary()) && motors->armed()) {
145  // 50hz loop
146  if (millis() - last_run_time < 20) {
147  // grab some compass values
149  hal.scheduler->delay(5);
150  continue;
151  }
152  last_run_time = millis();
153 
154  // read radio input
155  read_radio();
156 
157  // pass through throttle to motors
159  motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
161 
162  // read some compass values
163  compass.read();
164 
165  // read current
166  battery.read();
167 
168  // calculate scaling for throttle
169  throttle_pct = (float)channel_throttle->get_control_in() / 1000.0f;
170  throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);
171 
172  // if throttle is near zero, update base x,y,z values
173  if (throttle_pct <= 0.0f) {
174  for (uint8_t i=0; i<compass.get_count(); i++) {
175  compass_base[i] = compass_base[i] * 0.99f + compass.get_field(i) * 0.01f;
176  }
177 
178  // causing printing to happen as soon as throttle is lifted
179  } else {
180 
181  // calculate diff from compass base and scale with throttle
182  for (uint8_t i=0; i<compass.get_count(); i++) {
183  motor_impact[i] = compass.get_field(i) - compass_base[i];
184  }
185 
186  // throttle based compensation
187  if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
188  // for each compass
189  for (uint8_t i=0; i<compass.get_count(); i++) {
190  // scale by throttle
191  motor_impact_scaled[i] = motor_impact[i] / throttle_pct;
192  // adjust the motor compensation to negate the impact
193  motor_compensation[i] = motor_compensation[i] * 0.99f - motor_impact_scaled[i] * 0.01f;
194  }
195 
196  updated = true;
197  } else {
198  // for each compass
199  for (uint8_t i=0; i<compass.get_count(); i++) {
200  // current based compensation if more than 3amps being drawn
201  motor_impact_scaled[i] = motor_impact[i] / battery.current_amps();
202 
203  // adjust the motor compensation to negate the impact if drawing over 3amps
204  if (battery.current_amps() >= 3.0f) {
205  motor_compensation[i] = motor_compensation[i] * 0.99f - motor_impact_scaled[i] * 0.01f;
206  updated = true;
207  }
208  }
209  }
210 
211  // calculate interference percentage at full throttle as % of total mag field
212  if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
213  for (uint8_t i=0; i<compass.get_count(); i++) {
214  // interference is impact@fullthrottle / mag field * 100
215  interference_pct[i] = motor_compensation[i].length() / (float)arming.compass_magfield_expected() * 100.0f;
216  }
217  }else{
218  for (uint8_t i=0; i<compass.get_count(); i++) {
219  // interference is impact/amp * (max current seen / max throttle seen) / mag field * 100
220  interference_pct[i] = motor_compensation[i].length() * (current_amps_max/throttle_pct_max) / (float)arming.compass_magfield_expected() * 100.0f;
221  }
222  }
223 
224  // record maximum throttle and current
225  throttle_pct_max = MAX(throttle_pct_max, throttle_pct);
226  current_amps_max = MAX(current_amps_max, battery.current_amps());
227 
228  }
229  if (AP_HAL::millis() - last_send_time > 500) {
230  last_send_time = AP_HAL::millis();
231  mavlink_msg_compassmot_status_send(chan,
234  interference_pct[compass.get_primary()],
235  motor_compensation[compass.get_primary()].x,
236  motor_compensation[compass.get_primary()].y,
237  motor_compensation[compass.get_primary()].z);
238  }
239  }
240 
241  // stop motors
242  motors->output_min();
243  motors->armed(false);
244 
245  // set and save motor compensation
246  if (updated) {
247  compass.motor_compensation_type(comp_type);
248  for (uint8_t i=0; i<compass.get_count(); i++) {
249  compass.set_motor_compensation(i, motor_compensation[i]);
250  }
252  // display success message
253  gcs_chan.send_text(MAV_SEVERITY_INFO, "Calibration successful");
254  } else {
255  // compensation vector never updated, report failure
256  gcs_chan.send_text(MAV_SEVERITY_NOTICE, "Failed");
258  }
259 
260  // display new motor offsets and save
261  report_compass();
262 
263  // turn off notify leds
265 
266  // re-enable cpu failsafe
267  failsafe_enable();
268 
269  // re-enable failsafes
270  g.failsafe_throttle.load();
271 
272  // flag we have completed
273  ap.compass_mot = false;
274 
275  return MAV_RESULT_ACCEPTED;
276 #endif // FRAME_CONFIG != HELI_FRAME
277 }
278 
#define AP_COMPASS_MOT_COMP_DISABLED
void read_radio()
Definition: radio.cpp:94
AP_Arming_Copter arming
Definition: Copter.h:280
void failsafe_disable()
Definition: failsafe.cpp:27
MAV_RESULT mavlink_compassmot(mavlink_channel_t chan)
Definition: compassmot.cpp:8
void init_rc_out()
Definition: radio.cpp:52
GCS_Copter & gcs()
Definition: Copter.h:301
void accumulate()
bool read()
#define AP_COMPASS_MOT_COMP_THROTTLE
static void push()
void set_motor_compensation(uint8_t i, const Vector3f &motor_comp_factor)
bool rc_calibration_checks(bool display_failure) override
Definition: AP_Arming.cpp:349
void report_compass()
Definition: setup.cpp:4
MOTOR_CLASS * motors
Definition: Copter.h:422
uint8_t get_primary(void) const
const Vector3f & get_field(uint8_t i) const
virtual void delay(uint16_t ms)=0
RC_Channel * channel_throttle
Definition: Copter.h:223
int16_t get_control_in() const
#define f(i)
AP_BattMonitor battery
Definition: Copter.h:445
bool has_current(uint8_t instance) const
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
void init_compass()
Definition: sensors.cpp:90
#define FS_THR_DISABLED
Definition: defines.h:455
uint32_t millis()
GCS_MAVLINK_Copter & chan(const uint8_t ofs) override
Definition: GCS_Copter.h:16
bool healthy[COMPASS_MAX_INSTANCES]
float current_amps(uint8_t instance) const
uint16_t compass_magfield_expected() const
float length(void) const
uint8_t get_count(void) const
Parameters g
Definition: Copter.h:208
float constrain_float(const float amt, const float low, const float high)
#define COMPASS_MAX_INSTANCES
AP_Int8 compass_enabled
Definition: Parameters.h:401
uint8_t command_ack_counter
Definition: Copter.h:218
void motor_compensation_type(const uint8_t comp_type)
Compass compass
Definition: Copter.h:235
static struct notify_flags_and_values_type flags
static void cork()
AP_Int8 failsafe_throttle
Definition: Parameters.h:421
#define AP_COMPASS_MOT_COMP_CURRENT
void enable_motor_output()
Definition: radio.cpp:88
AP_HAL::Scheduler * scheduler
void failsafe_enable()
Definition: failsafe.cpp:18
void save_motor_compensation()