Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/esc_calibration.cpp
Views: 1798
#include "Copter.h"12/*****************************************************************************3* Functions to check and perform ESC calibration4*****************************************************************************/56#define ESC_CALIBRATION_HIGH_THROTTLE 95078// check if we should enter esc calibration mode9void Copter::esc_calibration_startup_check()10{11if (motors->is_brushed_pwm_type()) {12// ESC cal not valid for brushed motors13return;14}1516#if FRAME_CONFIG != HELI_FRAME17// delay up to 2 second for first radio input18uint8_t i = 0;19while ((i++ < 100) && (last_radio_update_ms == 0)) {20hal.scheduler->delay(20);21read_radio();22}2324// exit immediately if pre-arm rc checks fail25if (!arming.rc_calibration_checks(true)) {26// clear esc flag for next time27if ((g.esc_calibrate != ESCCalibrationModes::ESCCAL_NONE) && (g.esc_calibrate != ESCCalibrationModes::ESCCAL_DISABLED)) {28g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_NONE);29}30return;31}3233// check ESC parameter34switch (g.esc_calibrate) {35case ESCCalibrationModes::ESCCAL_NONE:36// check if throttle is high37if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {38// we will enter esc_calibrate mode on next reboot39g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);40// send message to gcs41gcs().send_text(MAV_SEVERITY_CRITICAL,"ESC calibration: Restart board");42// turn on esc calibration notification43AP_Notify::flags.esc_calibration = true;44// block until we restart45while(1) { hal.scheduler->delay(5); }46}47break;48case ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH:49// check if throttle is high50if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {51// pass through pilot throttle to escs52esc_calibration_passthrough();53}54break;55case ESCCalibrationModes::ESCCAL_PASSTHROUGH_ALWAYS:56// pass through pilot throttle to escs57esc_calibration_passthrough();58break;59case ESCCalibrationModes::ESCCAL_AUTO:60// perform automatic ESC calibration61esc_calibration_auto();62break;63case ESCCalibrationModes::ESCCAL_DISABLED:64default:65// do nothing66break;67}6869// clear esc flag for next time70if (g.esc_calibrate != ESCCalibrationModes::ESCCAL_DISABLED) {71g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_NONE);72}73#endif // FRAME_CONFIG != HELI_FRAME74}7576// esc_calibration_passthrough - pass through pilot throttle to escs77void Copter::esc_calibration_passthrough()78{79#if FRAME_CONFIG != HELI_FRAME80// send message to GCS81gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");8283esc_calibration_setup();8485while(1) {86// flash LEDs87esc_calibration_notify();8889// read pilot input90read_radio();9192// we run at high rate to make oneshot ESCs happy. Normal ESCs93// will only see pulses at the RC_SPEED94hal.scheduler->delay(3);9596// pass through to motors97auto &srv = AP::srv();98srv.cork();99motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);100srv.push();101}102#endif // FRAME_CONFIG != HELI_FRAME103}104105// esc_calibration_auto - calibrate the ESCs automatically using a timer and no pilot input106void Copter::esc_calibration_auto()107{108#if FRAME_CONFIG != HELI_FRAME109// send message to GCS110gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");111112esc_calibration_setup();113114// raise throttle to maximum115auto &srv = AP::srv();116srv.cork();117motors->set_throttle_passthrough_for_esc_calibration(1.0f);118srv.push();119120// delay for 5 seconds while outputting pulses121uint32_t tstart = millis();122while (millis() - tstart < 5000) {123srv.cork();124motors->set_throttle_passthrough_for_esc_calibration(1.0f);125srv.push();126esc_calibration_notify();127hal.scheduler->delay(3);128}129130// block until we restart131while(1) {132srv.cork();133motors->set_throttle_passthrough_for_esc_calibration(0.0f);134srv.push();135esc_calibration_notify();136hal.scheduler->delay(3);137}138#endif // FRAME_CONFIG != HELI_FRAME139}140141// flash LEDs to notify the user that ESC calibration is happening142void Copter::esc_calibration_notify()143{144AP_Notify::flags.esc_calibration = true;145uint32_t now = AP_HAL::millis();146if (now - esc_calibration_notify_update_ms > 20) {147esc_calibration_notify_update_ms = now;148notify.update();149}150}151152void Copter::esc_calibration_setup()153{154// clear esc flag for next time155g.esc_calibrate.set_and_save(ESCCAL_NONE);156157if (motors->is_normal_pwm_type()) {158// run at full speed for oneshot ESCs (actually done on push)159motors->set_update_rate(g.rc_speed);160} else {161// reduce update rate to motors to 50Hz162motors->set_update_rate(50);163}164165// disable safety if requested166BoardConfig.init_safety();167168// wait for safety switch to be pressed169uint32_t tstart = 0;170while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {171const uint32_t tnow = AP_HAL::millis();172if (tnow - tstart >= 5000) {173gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");174tstart = tnow;175}176esc_calibration_notify();177hal.scheduler->delay(3);178}179180// arm and enable motors181motors->armed(true);182SRV_Channels::enable_by_mask(motors->get_motor_mask());183hal.util->set_soft_armed(true);184}185186187