Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/esc_calibration.cpp
9546 views
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
// check if we should enter esc calibration mode
10
void Copter::esc_calibration_startup_check()
11
{
12
if (g.esc_calibrate == ESCCalibrationModes::ESCCAL_DISABLED) {
13
// esc calibration disabled
14
return;
15
}
16
17
if (motors->is_brushed_pwm_type() || motors->is_digital_pwm_type()) {
18
// ESC cal not valid for brushed motors or DSHOT ESCs
19
return;
20
}
21
22
#if FRAME_CONFIG != HELI_FRAME
23
// delay up to 2 second for first radio input
24
uint8_t i = 0;
25
while ((i++ < 100) && (last_radio_update_ms == 0)) {
26
hal.scheduler->delay(20);
27
read_radio();
28
}
29
30
// exit immediately if pre-arm rc checks fail
31
if (!arming.rc_calibration_checks(true)) {
32
// clear esc flag for next time
33
if ((g.esc_calibrate != ESCCalibrationModes::ESCCAL_NONE)) {
34
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_NONE);
35
}
36
return;
37
}
38
39
// check ESC parameter
40
switch (g.esc_calibrate) {
41
case ESCCalibrationModes::ESCCAL_NONE:
42
// check if throttle is high
43
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
44
// we will enter esc_calibrate mode on next reboot
45
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
46
// send message to gcs
47
gcs().send_text(MAV_SEVERITY_CRITICAL,"ESC calibration: Restart board");
48
// turn on esc calibration notification
49
AP_Notify::flags.esc_calibration = true;
50
// block until we restart
51
while(1) { hal.scheduler->delay(5); }
52
}
53
break;
54
case ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH:
55
// check if throttle is high
56
if (channel_throttle->get_control_in() >= ESC_CALIBRATION_HIGH_THROTTLE) {
57
// pass through pilot throttle to escs
58
esc_calibration_passthrough();
59
}
60
break;
61
case ESCCalibrationModes::ESCCAL_PASSTHROUGH_ALWAYS:
62
// pass through pilot throttle to escs
63
esc_calibration_passthrough();
64
break;
65
case ESCCalibrationModes::ESCCAL_AUTO:
66
// perform automatic ESC calibration
67
esc_calibration_auto();
68
break;
69
case ESCCalibrationModes::ESCCAL_DISABLED:
70
default:
71
// do nothing
72
break;
73
}
74
75
// clear esc flag for next time
76
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_NONE);
77
78
#endif // FRAME_CONFIG != HELI_FRAME
79
}
80
81
// esc_calibration_passthrough - pass through pilot throttle to escs
82
void Copter::esc_calibration_passthrough()
83
{
84
#if FRAME_CONFIG != HELI_FRAME
85
// send message to GCS
86
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");
87
88
esc_calibration_setup();
89
90
while(1) {
91
// flash LEDs
92
esc_calibration_notify();
93
94
// read pilot input
95
read_radio();
96
97
// we run at high rate to make oneshot ESCs happy. Normal ESCs
98
// will only see pulses at the RC_SPEED
99
hal.scheduler->delay(3);
100
101
// pass through to motors
102
auto &srv = AP::srv();
103
srv.cork();
104
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
105
srv.push();
106
}
107
#endif // FRAME_CONFIG != HELI_FRAME
108
}
109
110
// esc_calibration_auto - calibrate the ESCs automatically using a timer and no pilot input
111
void Copter::esc_calibration_auto()
112
{
113
#if FRAME_CONFIG != HELI_FRAME
114
// send message to GCS
115
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");
116
117
esc_calibration_setup();
118
119
// raise throttle to maximum
120
auto &srv = AP::srv();
121
srv.cork();
122
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
123
srv.push();
124
125
// delay for 5 seconds while outputting pulses
126
uint32_t tstart = millis();
127
while (millis() - tstart < 5000) {
128
srv.cork();
129
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
130
srv.push();
131
esc_calibration_notify();
132
hal.scheduler->delay(3);
133
}
134
135
// block until we restart
136
while(1) {
137
srv.cork();
138
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
139
srv.push();
140
esc_calibration_notify();
141
hal.scheduler->delay(3);
142
}
143
#endif // FRAME_CONFIG != HELI_FRAME
144
}
145
146
// flash LEDs to notify the user that ESC calibration is happening
147
void Copter::esc_calibration_notify()
148
{
149
AP_Notify::flags.esc_calibration = true;
150
uint32_t now = AP_HAL::millis();
151
if (now - esc_calibration_notify_update_ms > 20) {
152
esc_calibration_notify_update_ms = now;
153
notify.update();
154
}
155
}
156
157
void Copter::esc_calibration_setup()
158
{
159
// clear esc flag for next time
160
g.esc_calibrate.set_and_save(ESCCAL_NONE);
161
162
if (motors->is_normal_pwm_type()) {
163
// run at full speed for oneshot ESCs (actually done on push)
164
motors->set_update_rate(g.rc_speed);
165
} else {
166
// reduce update rate to motors to 50Hz
167
motors->set_update_rate(50);
168
}
169
170
// disable safety if requested
171
BoardConfig.init_safety();
172
173
// wait for safety switch to be pressed
174
uint32_t tstart = 0;
175
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
176
const uint32_t tnow = AP_HAL::millis();
177
if (tnow - tstart >= 5000) {
178
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
179
tstart = tnow;
180
}
181
esc_calibration_notify();
182
hal.scheduler->delay(3);
183
}
184
185
// arm and enable motors
186
motors->armed(true);
187
SRV_Channels::enable_by_mask(motors->get_motor_mask());
188
hal.util->set_soft_armed(true);
189
}
190
191