forked from bugobliterator/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcontrol_modes.cpp
295 lines (259 loc) · 8.18 KB
/
control_modes.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
#include "Rover.h"
static const int16_t CH_7_PWM_TRIGGER = 1800;
Mode *Rover::mode_from_mode_num(const enum mode num)
{
Mode *ret = nullptr;
switch (num) {
case MANUAL:
ret = &mode_manual;
break;
case ACRO:
ret = &mode_acro;
break;
case STEERING:
ret = &mode_steering;
break;
case HOLD:
ret = &mode_hold;
break;
case AUTO:
ret = &mode_auto;
break;
case RTL:
ret = &mode_rtl;
break;
case SMART_RTL:
ret = &mode_smartrtl;
break;
case GUIDED:
ret = &mode_guided;
break;
case INITIALISING:
ret = &mode_initializing;
break;
default:
break;
}
return ret;
}
void Rover::read_control_switch()
{
static bool switch_debouncer;
const uint8_t switchPosition = readSwitch();
// If switchPosition = 255 this indicates that the mode control channel input was out of range
// If we get this value we do not want to change modes.
if (switchPosition == 255) {
return;
}
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 100) {
// only use signals that are less than 0.1s old.
return;
}
// we look for changes in the switch position. If the
// RST_SWITCH_CH parameter is set, then it is a switch that can be
// used to force re-reading of the control switch. This is useful
// when returning to the previous mode after a failsafe or fence
// breach. This channel is best used on a momentary switch (such
// as a spring loaded trainer switch).
if (oldSwitchPosition != switchPosition ||
(g.reset_switch_chan != 0 &&
hal.rcin->read(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
if (switch_debouncer == false) {
// this ensures that mode switches only happen if the
// switch changes for 2 reads. This prevents momentary
// spikes in the mode control channel from causing a mode
// switch
switch_debouncer = true;
return;
}
Mode *new_mode = mode_from_mode_num((enum mode)modes[switchPosition].get());
if (new_mode != nullptr) {
set_mode(*new_mode, MODE_REASON_TX_COMMAND);
}
oldSwitchPosition = switchPosition;
}
switch_debouncer = false;
}
uint8_t Rover::readSwitch(void) {
const uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) {
return 255; // This is an error condition
}
if (pulsewidth <= 1230) {
return 0;
}
if (pulsewidth <= 1360) {
return 1;
}
if (pulsewidth <= 1490) {
return 2;
}
if (pulsewidth <= 1620) {
return 3;
}
if (pulsewidth <= 1749) {
return 4; // Software Manual
}
return 5; // Hardware Manual
}
void Rover::reset_control_switch()
{
oldSwitchPosition = 254;
read_control_switch();
}
// ready auxiliary switch's position
aux_switch_pos Rover::read_aux_switch_pos()
{
const uint16_t radio_in = channel_aux->get_radio_in();
if (radio_in < AUX_SWITCH_PWM_TRIGGER_LOW) return AUX_SWITCH_LOW;
if (radio_in > AUX_SWITCH_PWM_TRIGGER_HIGH) return AUX_SWITCH_HIGH;
return AUX_SWITCH_MIDDLE;
}
// initialise position of auxiliary switch
void Rover::init_aux_switch()
{
aux_ch7 = read_aux_switch_pos();
}
// read ch7 aux switch
void Rover::read_aux_switch()
{
// do not consume input during rc or throttle failsafe
if ((failsafe.bits & FAILSAFE_EVENT_THROTTLE) || (failsafe.bits & FAILSAFE_EVENT_RC)) {
return;
}
// get ch7's current position
aux_switch_pos aux_ch7_pos = read_aux_switch_pos();
// return if no change to switch position
if (aux_ch7_pos == aux_ch7) {
return;
}
aux_ch7 = aux_ch7_pos;
switch ((enum ch7_option)g.ch7_option.get()) {
case CH7_DO_NOTHING:
break;
case CH7_SAVE_WP:
if (aux_ch7 == AUX_SWITCH_HIGH) {
// do nothing if in AUTO mode
if (control_mode == &mode_auto) {
return;
}
// if disarmed clear mission and set home to current location
if (!arming.is_armed()) {
mission.clear();
set_home_to_current_location(false);
return;
}
// record the waypoint if not in auto mode
if (control_mode != &mode_auto) {
// create new mission command
AP_Mission::Mission_Command cmd = {};
// set new waypoint to current location
cmd.content.location = current_loc;
// make the new command to a waypoint
cmd.id = MAV_CMD_NAV_WAYPOINT;
// save command
if (mission.add_cmd(cmd)) {
hal.console->printf("Added waypoint %u", static_cast<uint32_t>(mission.num_commands()));
}
}
}
break;
// learn cruise speed and throttle
case CH7_LEARN_CRUISE:
if (aux_ch7 == AUX_SWITCH_HIGH) {
cruise_learn_start();
} else if (aux_ch7 == AUX_SWITCH_LOW) {
cruise_learn_complete();
}
break;
// arm or disarm the motors
case CH7_ARM_DISARM:
if (aux_ch7 == AUX_SWITCH_HIGH) {
arm_motors(AP_Arming::RUDDER);
} else if (aux_ch7 == AUX_SWITCH_LOW) {
disarm_motors();
}
break;
// set mode to Manual
case CH7_MANUAL:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_manual, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_manual)) {
reset_control_switch();
}
break;
// set mode to Acro
case CH7_ACRO:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_acro, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_acro)) {
reset_control_switch();
}
break;
// set mode to Steering
case CH7_STEERING:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_steering, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_steering)) {
reset_control_switch();
}
break;
// set mode to Hold
case CH7_HOLD:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_hold, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_hold)) {
reset_control_switch();
}
break;
// set mode to Auto
case CH7_AUTO:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_auto, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_auto)) {
reset_control_switch();
}
break;
// set mode to RTL
case CH7_RTL:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_rtl, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_rtl)) {
reset_control_switch();
}
break;
// set mode to SmartRTL
case CH7_SMART_RTL:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_smartrtl, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_smartrtl)) {
reset_control_switch();
}
break;
// set mode to Guided
case CH7_GUIDED:
if (aux_ch7 == AUX_SWITCH_HIGH) {
set_mode(mode_guided, MODE_REASON_TX_COMMAND);
} else if ((aux_ch7 == AUX_SWITCH_LOW) && (control_mode == &mode_guided)) {
reset_control_switch();
}
break;
}
}
// return true if motors are moving
bool Rover::motor_active()
{
// if soft disarmed, motors not active
if (!hal.util->get_soft_armed()) {
return false;
}
// check throttle is active
if (!is_zero(g2.motors.get_throttle())) {
return true;
}
// skid-steering vehicles active when steering
if (g2.motors.have_skid_steering() && !is_zero(g2.motors.get_steering())) {
return true;
}
return false;
}