Copter: fix compassmot for oneshot ESCs

This commit is contained in:
Randy Mackay 2017-05-23 13:11:08 +09:00
parent c459a25194
commit a0c5ac1949
1 changed files with 2 additions and 0 deletions

View File

@ -155,7 +155,9 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
read_radio();
// pass through throttle to motors
hal.rcout->cork();
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
hal.rcout->push();
// read some compass values
compass.read();