APM:Copter
esc_calibration.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*****************************************************************************
4 * Functions to check and perform ESC calibration
5 *****************************************************************************/
6 
7 #define ESC_CALIBRATION_HIGH_THROTTLE 950
8 
9 // enum for ESC CALIBRATION
16 };
17 
18 // check if we should enter esc calibration mode
20 {
21  if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) {
22  // ESC cal not valid for brushed motors
23  return;
24  }
25 
26 #if FRAME_CONFIG != HELI_FRAME
27  // delay up to 2 second for first radio input
28  uint8_t i = 0;
29  while ((i++ < 100) && (last_radio_update_ms == 0)) {
30  delay(20);
31  read_radio();
32  }
33 
34  // exit immediately if pre-arm rc checks fail
35  if (!arming.rc_calibration_checks(true)) {
36  // clear esc flag for next time
38  g.esc_calibrate.set_and_save(ESCCAL_NONE);
39  }
40  return;
41  }
42 
43  // check ESC parameter
44  switch (g.esc_calibrate) {
45  case ESCCAL_NONE:
46  // check if throttle is high
48  // we will enter esc_calibrate mode on next reboot
50  // send message to gcs
51  gcs().send_text(MAV_SEVERITY_CRITICAL,"ESC calibration: Restart board");
52  // turn on esc calibration notification
54  // block until we restart
55  while(1) { delay(5); }
56  }
57  break;
59  // check if throttle is high
61  // pass through pilot throttle to escs
63  }
64  break;
66  // pass through pilot throttle to escs
68  break;
69  case ESCCAL_AUTO:
70  // perform automatic ESC calibration
72  break;
73  case ESCCAL_DISABLED:
74  default:
75  // do nothing
76  break;
77  }
78 
79  // clear esc flag for next time
81  g.esc_calibrate.set_and_save(ESCCAL_NONE);
82  }
83 #endif // FRAME_CONFIG != HELI_FRAME
84 }
85 
86 // esc_calibration_passthrough - pass through pilot throttle to escs
88 {
89 #if FRAME_CONFIG != HELI_FRAME
90  // clear esc flag for next time
91  g.esc_calibrate.set_and_save(ESCCAL_NONE);
92 
93  if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) {
94  // run at full speed for oneshot ESCs (actually done on push)
95  motors->set_update_rate(g.rc_speed);
96  } else {
97  // reduce update rate to motors to 50Hz
98  motors->set_update_rate(50);
99  }
100 
101  // send message to GCS
102  gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");
103 
104  // disable safety if requested
106 
107  // arm motors
108  motors->armed(true);
109  SRV_Channels::enable_by_mask(motors->get_motor_mask());
110  hal.util->set_soft_armed(true);
111 
112  while(1) {
113  // flash LEDs
115 
116  // read pilot input
117  read_radio();
118 
119  // we run at high rate to make oneshot ESCs happy. Normal ESCs
120  // will only see pulses at the RC_SPEED
121  delay(3);
122 
123  // pass through to motors
125  motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
127  }
128 #endif // FRAME_CONFIG != HELI_FRAME
129 }
130 
131 // esc_calibration_auto - calibrate the ESCs automatically using a timer and no pilot input
133 {
134 #if FRAME_CONFIG != HELI_FRAME
135  bool printed_msg = false;
136 
137  // clear esc flag for next time
138  g.esc_calibrate.set_and_save(ESCCAL_NONE);
139 
140  if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) {
141  // run at full speed for oneshot ESCs (actually done on push)
142  motors->set_update_rate(g.rc_speed);
143  } else {
144  // reduce update rate to motors to 50Hz
145  motors->set_update_rate(50);
146  }
147 
148  // send message to GCS
149  gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");
150 
151  // disable safety if requested
153 
154  // arm and enable motors
155  motors->armed(true);
156  SRV_Channels::enable_by_mask(motors->get_motor_mask());
157  hal.util->set_soft_armed(true);
158 
159  // flash LEDs
161 
162  // raise throttle to maximum
163  delay(10);
164 
165  // wait for safety switch to be pressed
167  if (!printed_msg) {
168  gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
169  printed_msg = true;
170  }
172  motors->set_throttle_passthrough_for_esc_calibration(1.0f);
175  delay(3);
176  }
177 
178  // delay for 5 seconds while outputting pulses
179  uint32_t tstart = millis();
180  while (millis() - tstart < 5000) {
181  motors->set_throttle_passthrough_for_esc_calibration(1.0f);
183  delay(3);
184  }
185 
186  // reduce throttle to minimum
187  motors->set_throttle_passthrough_for_esc_calibration(0.0f);
188 
189  // block until we restart
190  while(1) {
191  motors->set_throttle_passthrough_for_esc_calibration(0.0f);
193  delay(3);
194  }
195 #endif // FRAME_CONFIG != HELI_FRAME
196 }
197 
198 // flash LEDs to notify the user that ESC calibration is happening
200 {
202  uint32_t now = AP_HAL::millis();
203  if (now - esc_calibration_notify_update_ms > 20) {
205  notify.update();
206  }
207 }
void esc_calibration_auto()
AP_BoardConfig BoardConfig
Definition: Copter.h:381
void esc_calibration_passthrough()
void read_radio()
Definition: radio.cpp:94
AP_Arming_Copter arming
Definition: Copter.h:280
GCS_Copter & gcs()
Definition: Copter.h:301
uint32_t last_radio_update_ms
Definition: Copter.h:583
AP_HAL::Util * util
static void push()
AP_Int16 rc_speed
Definition: Parameters.h:466
bool rc_calibration_checks(bool display_failure) override
Definition: AP_Arming.cpp:349
MOTOR_CLASS * motors
Definition: Copter.h:422
void esc_calibration_notify()
RC_Channel * channel_throttle
Definition: Copter.h:223
int16_t get_control_in() const
uint32_t esc_calibration_notify_update_ms
Definition: Copter.h:586
AP_Int8 esc_calibrate
Definition: Parameters.h:439
#define f(i)
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
uint32_t millis()
AP_Notify notify
Definition: Copter.h:215
virtual enum safety_state safety_switch_state(void)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Parameters g
Definition: Copter.h:208
void set_soft_armed(const bool b)
#define ESC_CALIBRATION_HIGH_THROTTLE
static struct notify_flags_and_values_type flags
ESCCalibrationModes
void esc_calibration_startup_check()
static void cork()
void update(void)
void init_safety(void)
static void enable_by_mask(uint16_t mask)
void delay(uint32_t ms)
Definition: compat.cpp:3