Browse Source

Copter: fix compassmot for oneshot ESCs

master
Randy Mackay 8 years ago
parent
commit
a0c5ac1949
  1. 2
      ArduCopter/compassmot.cpp

2
ArduCopter/compassmot.cpp

@ -155,7 +155,9 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) @@ -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…
Cancel
Save