Browse Source

Copter: remove compassmot's compass init and accumulate

when compass mot is started, the main loop has been running so the compass will already have been initialised and have good readings
Also remove unnecessary call to get_primary compass
mission-4.1.18
Randy Mackay 7 years ago
parent
commit
f30d999e0b
  1. 9
      ArduCopter/compassmot.cpp

9
ArduCopter/compassmot.cpp

@ -82,9 +82,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) @@ -82,9 +82,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
// disable cpu failsafe
failsafe_disable();
// initialise compass
init_compass();
// default compensation type to use current if possible
if (battery.has_current()) {
comp_type = AP_COMPASS_MOT_COMP_CURRENT;
@ -118,10 +115,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) @@ -118,10 +115,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
}
// get initial compass readings
last_run_time = millis();
while ( millis() - last_run_time < 500 ) {
compass.accumulate();
}
compass.read();
// store initial x,y,z compass values
@ -141,7 +134,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) @@ -141,7 +134,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
last_send_time = millis();
// main run while there is no user input and the compass is healthy
while (command_ack_start == command_ack_counter && compass.healthy(compass.get_primary()) && motors->armed()) {
while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) {
// 50hz loop
if (millis() - last_run_time < 20) {
// grab some compass values

Loading…
Cancel
Save