mirror of https://github.com/ArduPilot/ardupilot
Copter: init_rc_out in cli's compassmot setup
Bug fix to allow cli's compass motor compensation to be run from the mission planner's terminal window
This commit is contained in:
parent
6269b8029c
commit
d0fb332e9f
|
@ -548,7 +548,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv)
|
|||
}
|
||||
|
||||
// enable motors and pass through throttle
|
||||
motors.enable();
|
||||
init_rc_out();
|
||||
motors.armed(true);
|
||||
motors.output_min();
|
||||
|
||||
|
|
Loading…
Reference in New Issue