mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
Copter: prevent reset on compassmot due to watchdog
This commit is contained in:
parent
59669209fe
commit
92741c4e80
@ -124,6 +124,8 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
interference_pct[i] = 0.0f;
|
interference_pct[i] = 0.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
hal.scheduler->expect_delay_ms(5000);
|
||||||
|
|
||||||
// enable motors and pass through throttle
|
// enable motors and pass through throttle
|
||||||
init_rc_out();
|
init_rc_out();
|
||||||
enable_motor_output();
|
enable_motor_output();
|
||||||
@ -135,6 +137,8 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
|
|
||||||
// main run while there is no user input and the compass is healthy
|
// main run while there is no user input and the compass is healthy
|
||||||
while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) {
|
while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) {
|
||||||
|
hal.scheduler->expect_delay_ms(5000);
|
||||||
|
|
||||||
// 50hz loop
|
// 50hz loop
|
||||||
if (millis() - last_run_time < 20) {
|
if (millis() - last_run_time < 20) {
|
||||||
// grab some compass values
|
// grab some compass values
|
||||||
@ -228,6 +232,8 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
|
|
||||||
// stop motors
|
// stop motors
|
||||||
motors->output_min();
|
motors->output_min();
|
||||||
motors->armed(false);
|
motors->armed(false);
|
||||||
|
Loading…
Reference in New Issue
Block a user