#include "Copter.h"
#define ESC_CALIBRATION_HIGH_THROTTLE 950
void Copter::esc_calibration_startup_check()
{
if (g.esc_calibrate == ESCCalibrationModes::ESCCAL_DISABLED) {
return;
}
if (motors->is_brushed_pwm_type() || motors->is_digital_pwm_type()) {
return;
}
#if FRAME_CONFIG != HELI_FRAME
uint8_t i = 0;
while ((i++ < 100) && (last_radio_update_ms == 0)) {
hal.scheduler->delay(20);
read_radio();
}
if (!arming.rc_calibration_checks(true)) {
if ((g.esc_calibrate != ESCCalibrationModes::ESCCAL_NONE)) {
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_NONE);
}
return;
}
switch (g.esc_calibrate) {
case ESCCalibrationModes::ESCCAL_NONE:
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
gcs().send_text(MAV_SEVERITY_CRITICAL,"ESC calibration: Restart board");
AP_Notify::flags.esc_calibration = true;
while(1) { hal.scheduler->delay(5); }
}
break;
case ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH:
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
esc_calibration_passthrough();
}
break;
case ESCCalibrationModes::ESCCAL_PASSTHROUGH_ALWAYS:
esc_calibration_passthrough();
break;
case ESCCalibrationModes::ESCCAL_AUTO:
esc_calibration_auto();
break;
case ESCCalibrationModes::ESCCAL_DISABLED:
default:
break;
}
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_NONE);
#endif
}
void Copter::esc_calibration_passthrough()
{
#if FRAME_CONFIG != HELI_FRAME
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");
esc_calibration_setup();
while(1) {
esc_calibration_notify();
read_radio();
hal.scheduler->delay(3);
auto &srv = AP::srv();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
srv.push();
}
#endif
}
void Copter::esc_calibration_auto()
{
#if FRAME_CONFIG != HELI_FRAME
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");
esc_calibration_setup();
auto &srv = AP::srv();
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
srv.push();
uint32_t tstart = millis();
while (millis() - tstart < 5000) {
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
srv.push();
esc_calibration_notify();
hal.scheduler->delay(3);
}
while(1) {
srv.cork();
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
srv.push();
esc_calibration_notify();
hal.scheduler->delay(3);
}
#endif
}
void Copter::esc_calibration_notify()
{
AP_Notify::flags.esc_calibration = true;
uint32_t now = AP_HAL::millis();
if (now - esc_calibration_notify_update_ms > 20) {
esc_calibration_notify_update_ms = now;
notify.update();
}
}
void Copter::esc_calibration_setup()
{
g.esc_calibrate.set_and_save(ESCCAL_NONE);
if (motors->is_normal_pwm_type()) {
motors->set_update_rate(g.rc_speed);
} else {
motors->set_update_rate(50);
}
BoardConfig.init_safety();
uint32_t tstart = 0;
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
const uint32_t tnow = AP_HAL::millis();
if (tnow - tstart >= 5000) {
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
tstart = tnow;
}
esc_calibration_notify();
hal.scheduler->delay(3);
}
motors->armed(true);
SRV_Channels::enable_by_mask(motors->get_motor_mask());
hal.util->set_soft_armed(true);
}