ardupilot/ArduCopter/esc_calibration.cpp

203 lines
6.2 KiB
C++
Raw Normal View History

#include "Copter.h"
2015-04-16 01:27:06 -03:00
/*****************************************************************************
* Functions to check and perform ESC calibration
2015-04-16 01:27:06 -03:00
*****************************************************************************/
#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,
2015-04-16 01:27:06 -03:00
};
// check if we should enter esc calibration mode
void Copter::esc_calibration_startup_check()
2015-04-16 01:27:06 -03:00
{
#if FRAME_CONFIG != HELI_FRAME
// delay up to 2 second for first radio input
uint8_t i = 0;
while ((i++ < 100) && (last_radio_update_ms == 0)) {
delay(20);
read_radio();
}
2015-04-16 01:27:06 -03:00
// exit immediately if pre-arm rc checks fail
if (!arming.rc_calibration_checks(true)) {
2015-04-16 01:27:06 -03:00
// clear esc flag for next time
if ((g.esc_calibrate != ESCCAL_NONE) && (g.esc_calibrate != ESCCAL_DISABLED)) {
2015-04-16 01:27:06 -03:00
g.esc_calibrate.set_and_save(ESCCAL_NONE);
}
return;
}
// check ESC parameter
switch (g.esc_calibrate) {
case ESCCAL_NONE:
// check if throttle is high
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
2015-04-16 01:27:06 -03:00
// 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");
2015-04-16 01:27:06 -03:00
// 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
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
2015-04-16 01:27:06 -03:00
// 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:
2015-04-16 01:27:06 -03:00
default:
// do nothing
break;
}
2015-04-16 01:27:06 -03:00
// 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
2015-04-16 01:27:06 -03:00
}
// esc_calibration_passthrough - pass through pilot throttle to escs
void Copter::esc_calibration_passthrough()
2015-04-16 01:27:06 -03:00
{
#if FRAME_CONFIG != HELI_FRAME
2015-04-16 01:27:06 -03:00
// 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);
}
2015-04-16 01:27:06 -03:00
// send message to GCS
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");
2015-04-16 01:27:06 -03:00
// disable safety if requested
BoardConfig.init_safety();
// arm motors
motors->armed(true);
SRV_Channels::enable_by_mask(motors->get_motor_mask());
hal.util->set_soft_armed(true);
2015-04-16 01:27:06 -03:00
while(1) {
// flash LEDs
esc_calibration_notify();
2015-04-16 01:27:06 -03:00
// read pilot input
read_radio();
// we run at high rate to make oneshot ESCs happy. Normal ESCs
// will only see pulses at the RC_SPEED
delay(3);
2015-04-16 01:27:06 -03:00
// pass through to motors
2017-11-02 23:35:14 -03:00
SRV_Channels::cork();
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
2017-11-02 23:35:14 -03:00
SRV_Channels::push();
2015-04-16 01:27:06 -03:00
}
#endif // FRAME_CONFIG != HELI_FRAME
2015-04-16 01:27:06 -03:00
}
// esc_calibration_auto - calibrate the ESCs automatically using a timer and no pilot input
void Copter::esc_calibration_auto()
2015-04-16 01:27:06 -03:00
{
#if FRAME_CONFIG != HELI_FRAME
2015-04-16 01:27:06 -03:00
bool printed_msg = false;
// 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);
}
2015-04-16 01:27:06 -03:00
// send message to GCS
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");
2015-04-16 01:27:06 -03:00
// disable safety if requested
BoardConfig.init_safety();
2015-04-16 01:27:06 -03:00
// arm and enable motors
motors->armed(true);
SRV_Channels::enable_by_mask(motors->get_motor_mask());
hal.util->set_soft_armed(true);
2015-04-16 01:27:06 -03:00
// flash LEDs
esc_calibration_notify();
2015-04-16 01:27:06 -03:00
// 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");
2015-04-16 01:27:06 -03:00
printed_msg = true;
}
2017-11-02 23:35:14 -03:00
SRV_Channels::cork();
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
2017-11-02 23:35:14 -03:00
SRV_Channels::push();
esc_calibration_notify();
delay(3);
2015-04-16 01:27:06 -03:00
}
// delay for 5 seconds while outputting pulses
uint32_t tstart = millis();
while (millis() - tstart < 5000) {
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
esc_calibration_notify();
delay(3);
}
2015-04-16 01:27:06 -03:00
// reduce throttle to minimum
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
2015-04-16 01:27:06 -03:00
// block until we restart
while(1) {
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
esc_calibration_notify();
delay(3);
}
#endif // FRAME_CONFIG != HELI_FRAME
2015-04-16 01:27:06 -03:00
}
// flash LEDs to notify the user that ESC calibration is happening
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;
update_notify();
}
}