Copter: pass throttle for esc calibration in 0 to 1 range

This commit is contained in:
Randy Mackay 2016-05-21 15:48:19 +09:00
parent 49b14b3cb6
commit f28666e7cd
2 changed files with 4 additions and 4 deletions

View File

@ -157,7 +157,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
read_radio();
// pass through throttle to motors
motors.throttle_pass_through(channel_throttle->get_radio_in());
motors.set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
// read some compass values
compass.read();

View File

@ -100,7 +100,7 @@ void Copter::esc_calibration_passthrough()
delay(10);
// pass through to motors
motors.throttle_pass_through(channel_throttle->get_radio_in());
motors.set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
}
#endif // FRAME_CONFIG != HELI_FRAME
}
@ -126,7 +126,7 @@ void Copter::esc_calibration_auto()
// raise throttle to maximum
delay(10);
motors.throttle_pass_through(channel_throttle->get_radio_max());
motors.set_throttle_passthrough_for_esc_calibration(1.0f);
// wait for safety switch to be pressed
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
@ -141,7 +141,7 @@ void Copter::esc_calibration_auto()
delay(5000);
// reduce throttle to minimum
motors.throttle_pass_through(channel_throttle->get_radio_min());
motors.set_throttle_passthrough_for_esc_calibration(0.0f);
// clear esc parameter
g.esc_calibrate.set_and_save(ESCCAL_NONE);