mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-13 03:18:29 -04:00
Copter: fix esc calibration for one-shot
the cork and push need to be done from the vehicle level
This commit is contained in:
parent
f618359041
commit
5fad98078f
@ -104,6 +104,7 @@ void Copter::esc_calibration_passthrough()
|
||||
motors->armed(true);
|
||||
motors->enable();
|
||||
SRV_Channels::enable_by_mask(motors->get_motor_mask());
|
||||
hal.util->set_soft_armed(true);
|
||||
|
||||
while(1) {
|
||||
// flash LEDs
|
||||
@ -117,7 +118,9 @@ void Copter::esc_calibration_passthrough()
|
||||
delay(3);
|
||||
|
||||
// pass through to motors
|
||||
hal.rcout->cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
|
||||
hal.rcout->push();
|
||||
}
|
||||
#endif // FRAME_CONFIG != HELI_FRAME
|
||||
}
|
||||
@ -149,6 +152,7 @@ void Copter::esc_calibration_auto()
|
||||
motors->armed(true);
|
||||
motors->enable();
|
||||
SRV_Channels::enable_by_mask(motors->get_motor_mask());
|
||||
hal.util->set_soft_armed(true);
|
||||
|
||||
// flash LEDs
|
||||
esc_calibration_notify();
|
||||
@ -162,7 +166,9 @@ void Copter::esc_calibration_auto()
|
||||
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
|
||||
printed_msg = true;
|
||||
}
|
||||
hal.rcout->cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||
hal.rcout->push();
|
||||
esc_calibration_notify();
|
||||
delay(3);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user