|
|
@ -81,23 +81,31 @@ void Copter::esc_calibration_passthrough() |
|
|
|
// clear esc flag for next time
|
|
|
|
// clear esc flag for next time
|
|
|
|
g.esc_calibrate.set_and_save(ESCCAL_NONE); |
|
|
|
g.esc_calibrate.set_and_save(ESCCAL_NONE); |
|
|
|
|
|
|
|
|
|
|
|
// reduce update rate to motors to 50Hz
|
|
|
|
if (motors.get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) { |
|
|
|
motors.set_update_rate(50); |
|
|
|
// run at full speed for oneshot ESCs (actually done on push)
|
|
|
|
|
|
|
|
motors.set_update_rate(g.rc_speed); |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
// reduce update rate to motors to 50Hz
|
|
|
|
|
|
|
|
motors.set_update_rate(50); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// send message to GCS
|
|
|
|
// send message to GCS
|
|
|
|
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs"); |
|
|
|
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs"); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// arm motors
|
|
|
|
|
|
|
|
motors.armed(true); |
|
|
|
|
|
|
|
motors.enable(); |
|
|
|
|
|
|
|
|
|
|
|
while(1) { |
|
|
|
while(1) { |
|
|
|
// arm motors
|
|
|
|
|
|
|
|
motors.armed(true); |
|
|
|
|
|
|
|
motors.enable(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// flash LEDS
|
|
|
|
// flash LEDS
|
|
|
|
AP_Notify::flags.esc_calibration = true; |
|
|
|
AP_Notify::flags.esc_calibration = true; |
|
|
|
|
|
|
|
|
|
|
|
// read pilot input
|
|
|
|
// read pilot input
|
|
|
|
read_radio(); |
|
|
|
read_radio(); |
|
|
|
delay(10); |
|
|
|
|
|
|
|
|
|
|
|
// we run at high rate do make oneshot ESCs happy. Normal ESCs
|
|
|
|
|
|
|
|
// will only see pulses at the RC_SPEED
|
|
|
|
|
|
|
|
delay(3); |
|
|
|
|
|
|
|
|
|
|
|
// pass through to motors
|
|
|
|
// pass through to motors
|
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f); |
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f); |
|
|
@ -111,8 +119,13 @@ void Copter::esc_calibration_auto() |
|
|
|
#if FRAME_CONFIG != HELI_FRAME |
|
|
|
#if FRAME_CONFIG != HELI_FRAME |
|
|
|
bool printed_msg = false; |
|
|
|
bool printed_msg = false; |
|
|
|
|
|
|
|
|
|
|
|
// reduce update rate to motors to 50Hz
|
|
|
|
if (motors.get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) { |
|
|
|
motors.set_update_rate(50); |
|
|
|
// run at full speed for oneshot ESCs (actually done on push)
|
|
|
|
|
|
|
|
motors.set_update_rate(g.rc_speed); |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
// reduce update rate to motors to 50Hz
|
|
|
|
|
|
|
|
motors.set_update_rate(50); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// send message to GCS
|
|
|
|
// send message to GCS
|
|
|
|
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration"); |
|
|
|
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration"); |
|
|
@ -126,7 +139,6 @@ void Copter::esc_calibration_auto() |
|
|
|
|
|
|
|
|
|
|
|
// raise throttle to maximum
|
|
|
|
// raise throttle to maximum
|
|
|
|
delay(10); |
|
|
|
delay(10); |
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(1.0f); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// wait for safety switch to be pressed
|
|
|
|
// wait for safety switch to be pressed
|
|
|
|
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) { |
|
|
|
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) { |
|
|
@ -134,11 +146,16 @@ void Copter::esc_calibration_auto() |
|
|
|
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch"); |
|
|
|
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch"); |
|
|
|
printed_msg = true; |
|
|
|
printed_msg = true; |
|
|
|
} |
|
|
|
} |
|
|
|
delay(10); |
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(1.0f); |
|
|
|
|
|
|
|
delay(3); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// delay for 5 seconds
|
|
|
|
// delay for 5 seconds while outputting pulses
|
|
|
|
delay(5000); |
|
|
|
uint32_t tstart = millis(); |
|
|
|
|
|
|
|
while (millis() - tstart < 5000) { |
|
|
|
|
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(1.0f); |
|
|
|
|
|
|
|
delay(3); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// reduce throttle to minimum
|
|
|
|
// reduce throttle to minimum
|
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(0.0f); |
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(0.0f); |
|
|
@ -147,6 +164,9 @@ void Copter::esc_calibration_auto() |
|
|
|
g.esc_calibrate.set_and_save(ESCCAL_NONE); |
|
|
|
g.esc_calibrate.set_and_save(ESCCAL_NONE); |
|
|
|
|
|
|
|
|
|
|
|
// block until we restart
|
|
|
|
// block until we restart
|
|
|
|
while(1) { delay(5); } |
|
|
|
while(1) { |
|
|
|
|
|
|
|
delay(3); |
|
|
|
|
|
|
|
motors.set_throttle_passthrough_for_esc_calibration(0.0f); |
|
|
|
|
|
|
|
} |
|
|
|
#endif // FRAME_CONFIG != HELI_FRAME
|
|
|
|
#endif // FRAME_CONFIG != HELI_FRAME
|
|
|
|
} |
|
|
|
} |
|
|
|