ardupilot/ArduCopter/esc_calibration.cpp
Randy Mackay 6726d94537 Copter: update notify during ESC calibration
The notify devices including the RGB were not being updated meaning the main LED was normally frozen or off during calibration.  The desired behaviour is that it flashes red, blue, yellow.
2017-01-27 12:14:56 +09:00

177 lines
5.5 KiB
C++

#include "Copter.h"
/*****************************************************************************
* Functions to check and perform ESC calibration
*****************************************************************************/
#define ESC_CALIBRATION_HIGH_THROTTLE 950
// enum for ESC CALIBRATION
enum ESCCalibrationModes {
ESCCAL_NONE = 0,
ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH = 1,
ESCCAL_PASSTHROUGH_ALWAYS = 2,
ESCCAL_AUTO = 3,
ESCCAL_DISABLED = 9,
};
// check if we should enter esc calibration mode
void Copter::esc_calibration_startup_check()
{
#if FRAME_CONFIG != HELI_FRAME
// exit immediately if pre-arm rc checks fail
arming.pre_arm_rc_checks(true);
if (!ap.pre_arm_rc_check) {
// clear esc flag for next time
if ((g.esc_calibrate != ESCCAL_NONE) && (g.esc_calibrate != ESCCAL_DISABLED)) {
g.esc_calibrate.set_and_save(ESCCAL_NONE);
}
return;
}
// check ESC parameter
switch (g.esc_calibrate) {
case ESCCAL_NONE:
// check if throttle is high
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
// we will enter esc_calibrate mode on next reboot
g.esc_calibrate.set_and_save(ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
// send message to gcs
gcs_send_text(MAV_SEVERITY_CRITICAL,"ESC calibration: Restart board");
// turn on esc calibration notification
AP_Notify::flags.esc_calibration = true;
// block until we restart
while(1) { delay(5); }
}
break;
case ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH:
// check if throttle is high
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
// pass through pilot throttle to escs
esc_calibration_passthrough();
}
break;
case ESCCAL_PASSTHROUGH_ALWAYS:
// pass through pilot throttle to escs
esc_calibration_passthrough();
break;
case ESCCAL_AUTO:
// perform automatic ESC calibration
esc_calibration_auto();
break;
case ESCCAL_DISABLED:
default:
// do nothing
break;
}
// clear esc flag for next time
if (g.esc_calibrate != ESCCAL_DISABLED) {
g.esc_calibrate.set_and_save(ESCCAL_NONE);
}
#endif // FRAME_CONFIG != HELI_FRAME
}
// esc_calibration_passthrough - pass through pilot throttle to escs
void Copter::esc_calibration_passthrough()
{
#if FRAME_CONFIG != HELI_FRAME
// clear esc flag for next time
g.esc_calibrate.set_and_save(ESCCAL_NONE);
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) {
// 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
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");
// arm motors
motors->armed(true);
motors->enable();
uint32_t last_notify_update_ms = 0;
while(1) {
// flash LEDS
AP_Notify::flags.esc_calibration = true;
uint32_t now = AP_HAL::millis();
if (now - last_notify_update_ms > 20) {
last_notify_update_ms = now;
update_notify();
}
// read pilot input
read_radio();
// 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
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
}
#endif // FRAME_CONFIG != HELI_FRAME
}
// esc_calibration_auto - calibrate the ESCs automatically using a timer and no pilot input
void Copter::esc_calibration_auto()
{
#if FRAME_CONFIG != HELI_FRAME
bool printed_msg = false;
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) {
// 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
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");
// arm and enable motors
motors->armed(true);
motors->enable();
// flash LEDS
AP_Notify::flags.esc_calibration = true;
// raise throttle to maximum
delay(10);
// wait for safety switch to be pressed
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
if (!printed_msg) {
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
printed_msg = true;
}
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
delay(3);
}
// delay for 5 seconds while outputting pulses
uint32_t tstart = millis();
while (millis() - tstart < 5000) {
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
delay(3);
}
// reduce throttle to minimum
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
// clear esc parameter
g.esc_calibrate.set_and_save(ESCCAL_NONE);
// block until we restart
while(1) {
delay(3);
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
}
#endif // FRAME_CONFIG != HELI_FRAME
}