mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: fix compassmot for oneshot ESCs
This commit is contained in:
parent
c459a25194
commit
a0c5ac1949
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user