CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/mode.cpp
Views: 1798
1
#include "Rover.h"
2
3
Mode::Mode() :
4
ahrs(rover.ahrs),
5
g(rover.g),
6
g2(rover.g2),
7
channel_steer(rover.channel_steer),
8
channel_throttle(rover.channel_throttle),
9
channel_lateral(rover.channel_lateral),
10
channel_roll(rover.channel_roll),
11
channel_pitch(rover.channel_pitch),
12
channel_walking_height(rover.channel_walking_height),
13
attitude_control(g2.attitude_control)
14
{ }
15
16
void Mode::exit()
17
{
18
// call sub-classes exit
19
_exit();
20
}
21
22
bool Mode::enter()
23
{
24
const bool ignore_checks = !hal.util->get_soft_armed(); // allow switching to any mode if disarmed. We rely on the arming check to perform
25
if (!ignore_checks) {
26
27
// get EKF filter status
28
nav_filter_status filt_status;
29
rover.ahrs.get_filter_status(filt_status);
30
31
// check position estimate. requires origin and at least one horizontal position flag to be true
32
const bool position_ok = rover.ekf_position_ok() && !rover.failsafe.ekf;
33
if (requires_position() && !position_ok) {
34
return false;
35
}
36
37
// check velocity estimate (if we have position estimate, we must have velocity estimate)
38
if (requires_velocity() && !position_ok && !filt_status.flags.horiz_vel) {
39
return false;
40
}
41
}
42
43
bool ret = _enter();
44
45
// initialisation common to all modes
46
if (ret) {
47
// init reversed flag
48
init_reversed_flag();
49
50
// clear sailboat tacking flags
51
g2.sailboat.clear_tack();
52
}
53
54
return ret;
55
}
56
57
// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments
58
// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise
59
// throttle_out is in the range -100 ~ +100
60
void Mode::get_pilot_input(float &steering_out, float &throttle_out) const
61
{
62
// no RC input means no throttle and centered steering
63
if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
64
steering_out = 0;
65
throttle_out = 0;
66
return;
67
}
68
69
// apply RC skid steer mixing
70
switch ((PilotSteerType)g.pilot_steer_type.get())
71
{
72
case PilotSteerType::DEFAULT:
73
case PilotSteerType::DIR_REVERSED_WHEN_REVERSING:
74
default: {
75
// by default regular and skid-steering vehicles reverse their rotation direction when backing up
76
throttle_out = rover.channel_throttle->get_control_in();
77
const float steering_dir = is_negative(throttle_out) ? -1 : 1;
78
steering_out = steering_dir * rover.channel_steer->get_control_in();
79
break;
80
}
81
82
case PilotSteerType::TWO_PADDLES: {
83
// convert the two radio_in values from skid steering values
84
// left paddle from steering input channel, right paddle from throttle input channel
85
// steering = left-paddle - right-paddle
86
// throttle = average(left-paddle, right-paddle)
87
const float left_paddle = rover.channel_steer->norm_input_dz();
88
const float right_paddle = rover.channel_throttle->norm_input_dz();
89
90
throttle_out = 0.5f * (left_paddle + right_paddle) * 100.0f;
91
steering_out = (left_paddle - right_paddle) * 0.5f * 4500.0f;
92
break;
93
}
94
95
case PilotSteerType::DIR_UNCHANGED_WHEN_REVERSING: {
96
throttle_out = rover.channel_throttle->get_control_in();
97
steering_out = rover.channel_steer->get_control_in();
98
break;
99
}
100
}
101
}
102
103
// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments
104
// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise
105
// throttle_out is in the range -100 ~ +100
106
void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &throttle_out) const
107
{
108
// do basic conversion
109
get_pilot_input(steering_out, throttle_out);
110
111
// for skid steering vehicles, if pilot commands would lead to saturation
112
// we proportionally reduce steering and throttle
113
if (g2.motors.have_skid_steering()) {
114
const float steer_normalised = constrain_float(steering_out / 4500.0f, -1.0f, 1.0f);
115
const float throttle_normalised = constrain_float(throttle_out * 0.01f, -1.0f, 1.0f);
116
const float saturation_value = fabsf(steer_normalised) + fabsf(throttle_normalised);
117
if (saturation_value > 1.0f) {
118
steering_out /= saturation_value;
119
throttle_out /= saturation_value;
120
}
121
}
122
123
// check for special case of input and output throttle being in opposite directions
124
float throttle_out_limited = g2.motors.get_slew_limited_throttle(throttle_out, rover.G_Dt);
125
if ((is_negative(throttle_out) != is_negative(throttle_out_limited)) &&
126
(g.pilot_steer_type == PilotSteerType::DEFAULT ||
127
g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) {
128
steering_out *= -1;
129
}
130
throttle_out = throttle_out_limited;
131
}
132
133
// decode pilot steering and return steering_out and speed_out (in m/s)
134
void Mode::get_pilot_desired_steering_and_speed(float &steering_out, float &speed_out) const
135
{
136
float desired_throttle;
137
get_pilot_input(steering_out, desired_throttle);
138
speed_out = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
139
// check for special case of input and output throttle being in opposite directions
140
float speed_out_limited = g2.attitude_control.get_desired_speed_accel_limited(speed_out, rover.G_Dt);
141
if ((is_negative(speed_out) != is_negative(speed_out_limited)) &&
142
(g.pilot_steer_type == PilotSteerType::DEFAULT ||
143
g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) {
144
steering_out *= -1;
145
}
146
speed_out = speed_out_limited;
147
}
148
149
// decode pilot lateral movement input and return in lateral_out argument
150
void Mode::get_pilot_desired_lateral(float &lateral_out) const
151
{
152
// no RC input means no lateral input
153
if ((rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) || (rover.channel_lateral == nullptr)) {
154
lateral_out = 0;
155
return;
156
}
157
158
// get pilot lateral input
159
lateral_out = rover.channel_lateral->get_control_in();
160
}
161
162
// decode pilot's input and return heading_out (in cd) and speed_out (in m/s)
163
void Mode::get_pilot_desired_heading_and_speed(float &heading_out, float &speed_out) const
164
{
165
// get steering and throttle in the -1 to +1 range
166
float desired_steering = constrain_float(rover.channel_steer->norm_input_dz(), -1.0f, 1.0f);
167
float desired_throttle = constrain_float(rover.channel_throttle->norm_input_dz(), -1.0f, 1.0f);
168
169
// handle two paddle input
170
if (g.pilot_steer_type == PilotSteerType::TWO_PADDLES) {
171
const float left_paddle = desired_steering;
172
const float right_paddle = desired_throttle;
173
desired_steering = (left_paddle - right_paddle) * 0.5f;
174
desired_throttle = (left_paddle + right_paddle) * 0.5f;
175
}
176
177
// calculate angle of input stick vector
178
heading_out = wrap_360_cd(atan2f(desired_steering, desired_throttle) * DEGX100);
179
180
// calculate throttle using magnitude of input stick vector
181
const float throttle = MIN(safe_sqrt(sq(desired_throttle) + sq(desired_steering)), 1.0f);
182
speed_out = throttle * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
183
}
184
185
// decode pilot roll and pitch inputs and return in roll_out and pitch_out arguments
186
// outputs are in the range -1 to +1
187
void Mode::get_pilot_desired_roll_and_pitch(float &roll_out, float &pitch_out) const
188
{
189
if (channel_roll != nullptr) {
190
roll_out = channel_roll->norm_input();
191
} else {
192
roll_out = 0.0f;
193
}
194
if (channel_pitch != nullptr) {
195
pitch_out = channel_pitch->norm_input();
196
} else {
197
pitch_out = 0.0f;
198
}
199
}
200
201
// decode pilot walking_height inputs and return in walking_height_out arguments
202
// outputs are in the range -1 to +1
203
void Mode::get_pilot_desired_walking_height(float &walking_height_out) const
204
{
205
if (channel_walking_height != nullptr) {
206
walking_height_out = channel_walking_height->norm_input();
207
} else {
208
walking_height_out = 0.0f;
209
}
210
}
211
212
// return heading (in degrees) to target destination (aka waypoint)
213
float Mode::wp_bearing() const
214
{
215
if (!is_autopilot_mode()) {
216
return 0.0f;
217
}
218
return g2.wp_nav.wp_bearing_cd() * 0.01f;
219
}
220
221
// return short-term target heading in degrees (i.e. target heading back to line between waypoints)
222
float Mode::nav_bearing() const
223
{
224
if (!is_autopilot_mode()) {
225
return 0.0f;
226
}
227
return g2.wp_nav.nav_bearing_cd() * 0.01f;
228
}
229
230
// return cross track error (i.e. vehicle's distance from the line between waypoints)
231
float Mode::crosstrack_error() const
232
{
233
if (!is_autopilot_mode()) {
234
return 0.0f;
235
}
236
return g2.wp_nav.crosstrack_error();
237
}
238
239
// return desired lateral acceleration
240
float Mode::get_desired_lat_accel() const
241
{
242
if (!is_autopilot_mode()) {
243
return 0.0f;
244
}
245
return g2.wp_nav.get_lat_accel();
246
}
247
248
// set desired location
249
bool Mode::set_desired_location(const Location &destination, Location next_destination )
250
{
251
if (!g2.wp_nav.set_desired_location(destination, next_destination)) {
252
return false;
253
}
254
255
// initialise distance
256
_distance_to_destination = g2.wp_nav.get_distance_to_destination();
257
_reached_destination = false;
258
259
return true;
260
}
261
262
// get default speed for this mode (held in WP_SPEED or RTL_SPEED)
263
float Mode::get_speed_default(bool rtl) const
264
{
265
if (rtl && is_positive(g2.rtl_speed)) {
266
return g2.rtl_speed;
267
}
268
269
return g2.wp_nav.get_default_speed();
270
}
271
272
// execute the mission in reverse (i.e. backing up)
273
void Mode::set_reversed(bool value)
274
{
275
g2.wp_nav.set_reversed(value);
276
}
277
278
// handle tacking request (from auxiliary switch) in sailboats
279
void Mode::handle_tack_request()
280
{
281
// autopilot modes handle tacking
282
if (is_autopilot_mode()) {
283
g2.sailboat.handle_tack_request_auto();
284
}
285
}
286
287
void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
288
{
289
// get acceleration limited target speed
290
target_speed = attitude_control.get_desired_speed_accel_limited(target_speed, rover.G_Dt);
291
292
#if AP_AVOIDANCE_ENABLED
293
// apply object avoidance to desired speed using half vehicle's maximum deceleration
294
if (avoidance_enabled) {
295
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw(), target_speed, rover.G_Dt);
296
if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {
297
// we are a sailboat trying to avoid fence, try a tack
298
if (rover.control_mode != &rover.mode_acro) {
299
rover.control_mode->handle_tack_request();
300
}
301
}
302
}
303
#endif // AP_AVOIDANCE_ENABLED
304
305
// call throttle controller and convert output to -100 to +100 range
306
float throttle_out = 0.0f;
307
308
if (g2.sailboat.sail_enabled()) {
309
// sailboats use special throttle and mainsail controller
310
g2.sailboat.get_throttle_and_set_mainsail(target_speed, throttle_out);
311
} else {
312
// call speed or stop controller
313
if (is_zero(target_speed) && !rover.is_balancebot()) {
314
bool stopped;
315
throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);
316
} else {
317
bool motor_lim_low = g2.motors.limit.throttle_lower || attitude_control.pitch_limited();
318
bool motor_lim_high = g2.motors.limit.throttle_upper || attitude_control.pitch_limited();
319
throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, motor_lim_low, motor_lim_high, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt);
320
}
321
322
// if vehicle is balance bot, calculate actual throttle required for balancing
323
if (rover.is_balancebot()) {
324
rover.balancebot_pitch_control(throttle_out);
325
}
326
}
327
328
// send to motor
329
g2.motors.set_throttle(throttle_out);
330
}
331
332
// performs a controlled stop without turning
333
bool Mode::stop_vehicle()
334
{
335
// call throttle controller and convert output to -100 to +100 range
336
bool stopped = false;
337
float throttle_out;
338
339
// if vehicle is balance bot, calculate throttle required for balancing
340
if (rover.is_balancebot()) {
341
throttle_out = 100.0f * attitude_control.get_throttle_out_speed(0, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt);
342
rover.balancebot_pitch_control(throttle_out);
343
} else {
344
throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped);
345
}
346
347
// relax sails if present
348
g2.sailboat.relax_sails();
349
350
// send to motor
351
g2.motors.set_throttle(throttle_out);
352
353
// do not turn while slowing down
354
float steering_out = 0.0;
355
if (!stopped) {
356
steering_out = attitude_control.get_steering_out_rate(0.0, g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt);
357
}
358
g2.motors.set_steering(steering_out * 4500.0);
359
360
// return true once stopped
361
return stopped;
362
}
363
364
// estimate maximum vehicle speed (in m/s)
365
// cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1
366
float Mode::calc_speed_max(float cruise_speed, float cruise_throttle) const
367
{
368
float speed_max;
369
370
// sanity checks
371
if (cruise_throttle > 1.0f || cruise_throttle < 0.05f) {
372
speed_max = cruise_speed;
373
} else if (is_positive(g2.speed_max)) {
374
speed_max = g2.speed_max;
375
} else {
376
// project vehicle's maximum speed
377
speed_max = (1.0f / cruise_throttle) * cruise_speed;
378
}
379
380
// constrain to 30m/s (108km/h) and return
381
return constrain_float(speed_max, 0.0f, 30.0f);
382
}
383
384
// calculate pilot input to nudge speed up or down
385
// target_speed should be in meters/sec
386
// reversed should be true if the vehicle is intentionally backing up which allows the pilot to increase the backing up speed by pulling the throttle stick down
387
float Mode::calc_speed_nudge(float target_speed, bool reversed)
388
{
389
// sanity checks
390
if (g.throttle_cruise > 100 || g.throttle_cruise < 5) {
391
return target_speed;
392
}
393
394
// convert pilot throttle input to speed
395
float pilot_steering, pilot_throttle;
396
get_pilot_input(pilot_steering, pilot_throttle);
397
float pilot_speed = pilot_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
398
399
// ignore pilot's input if in opposite direction to vehicle's desired direction of travel
400
// note that the target_speed may be negative while reversed is true (or vice-versa)
401
// while vehicle is transitioning between forward and backwards movement
402
if ((is_positive(pilot_speed) && reversed) ||
403
(is_negative(pilot_speed) && !reversed)) {
404
return target_speed;
405
}
406
407
// return the larger of the pilot speed and the original target speed
408
if (reversed) {
409
return MIN(target_speed, pilot_speed);
410
} else {
411
return MAX(target_speed, pilot_speed);
412
}
413
}
414
415
// high level call to navigate to waypoint
416
// uses wp_nav to calculate turn rate and speed to drive along the path from origin to destination
417
// this function updates _distance_to_destination
418
void Mode::navigate_to_waypoint()
419
{
420
// apply speed nudge from pilot
421
// calc_speed_nudge's "desired_speed" argument should be negative when vehicle is reversing
422
// AR_WPNav nudge_speed_max argu,ent should always be positive even when reversing
423
const float calc_nudge_input_speed = g2.wp_nav.get_speed_max() * (g2.wp_nav.get_reversed() ? -1.0 : 1.0);
424
const float nudge_speed_max = calc_speed_nudge(calc_nudge_input_speed, g2.wp_nav.get_reversed());
425
g2.wp_nav.set_nudge_speed_max(fabsf(nudge_speed_max));
426
427
// update navigation controller
428
g2.wp_nav.update(rover.G_Dt);
429
_distance_to_destination = g2.wp_nav.get_distance_to_destination();
430
431
#if AP_AVOIDANCE_ENABLED
432
// sailboats trigger tack if simple avoidance becomes active
433
if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {
434
// we are a sailboat trying to avoid fence, try a tack
435
rover.control_mode->handle_tack_request();
436
}
437
#endif
438
439
// pass desired speed to throttle controller
440
// do not do simple avoidance because this is already handled in the position controller
441
calc_throttle(g2.wp_nav.get_speed(), false);
442
443
float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd();
444
if (g2.sailboat.use_indirect_route(desired_heading_cd)) {
445
// sailboats use heading controller when tacking upwind
446
desired_heading_cd = g2.sailboat.calc_heading(desired_heading_cd);
447
// use pivot turn rate for tacks
448
const float turn_rate = g2.sailboat.tacking() ? g2.wp_nav.get_pivot_rate() : 0.0f;
449
calc_steering_to_heading(desired_heading_cd, turn_rate);
450
} else {
451
// retrieve turn rate from waypoint controller
452
float desired_turn_rate_rads = g2.wp_nav.get_turn_rate_rads();
453
454
// if simple avoidance is active at very low speed do not attempt to turn
455
#if AP_AVOIDANCE_ENABLED
456
if (g2.avoid.limits_active() && (fabsf(attitude_control.get_desired_speed()) <= attitude_control.get_stop_speed())) {
457
desired_turn_rate_rads = 0.0f;
458
}
459
#endif
460
461
// call turn rate steering controller
462
calc_steering_from_turn_rate(desired_turn_rate_rads);
463
}
464
}
465
466
// calculate steering output given a turn rate
467
// desired turn rate in radians/sec. Positive to the right.
468
void Mode::calc_steering_from_turn_rate(float turn_rate)
469
{
470
// calculate and send final steering command to motor library
471
const float steering_out = attitude_control.get_steering_out_rate(turn_rate,
472
g2.motors.limit.steer_left,
473
g2.motors.limit.steer_right,
474
rover.G_Dt);
475
set_steering(steering_out * 4500.0f);
476
}
477
478
/*
479
calculate steering output given lateral_acceleration
480
*/
481
void Mode::calc_steering_from_lateral_acceleration(float lat_accel, bool reversed)
482
{
483
// constrain to max G force
484
lat_accel = constrain_float(lat_accel, -attitude_control.get_turn_lat_accel_max(), attitude_control.get_turn_lat_accel_max());
485
486
// send final steering command to motor library
487
const float steering_out = attitude_control.get_steering_out_lat_accel(lat_accel,
488
g2.motors.limit.steer_left,
489
g2.motors.limit.steer_right,
490
rover.G_Dt);
491
set_steering(steering_out * 4500.0f);
492
}
493
494
// calculate steering output to drive towards desired heading
495
// rate_max is a maximum turn rate in deg/s. set to zero to use default turn rate limits
496
void Mode::calc_steering_to_heading(float desired_heading_cd, float rate_max_degs)
497
{
498
// call heading controller
499
const float steering_out = attitude_control.get_steering_out_heading(radians(desired_heading_cd*0.01f),
500
radians(rate_max_degs),
501
g2.motors.limit.steer_left,
502
g2.motors.limit.steer_right,
503
rover.G_Dt);
504
set_steering(steering_out * 4500.0f);
505
}
506
507
void Mode::set_steering(float steering_value)
508
{
509
if (allows_stick_mixing() && g2.stick_mixing > 0) {
510
steering_value = channel_steer->stick_mixing((int16_t)steering_value);
511
}
512
g2.motors.set_steering(steering_value);
513
}
514
515
Mode *Rover::mode_from_mode_num(const enum Mode::Number num)
516
{
517
Mode *ret = nullptr;
518
switch (num) {
519
case Mode::Number::MANUAL:
520
ret = &mode_manual;
521
break;
522
case Mode::Number::ACRO:
523
ret = &mode_acro;
524
break;
525
case Mode::Number::STEERING:
526
ret = &mode_steering;
527
break;
528
case Mode::Number::HOLD:
529
ret = &mode_hold;
530
break;
531
case Mode::Number::LOITER:
532
ret = &mode_loiter;
533
break;
534
#if MODE_FOLLOW_ENABLED
535
case Mode::Number::FOLLOW:
536
ret = &mode_follow;
537
break;
538
#endif
539
case Mode::Number::SIMPLE:
540
ret = &mode_simple;
541
break;
542
case Mode::Number::CIRCLE:
543
ret = &g2.mode_circle;
544
break;
545
case Mode::Number::AUTO:
546
ret = &mode_auto;
547
break;
548
case Mode::Number::RTL:
549
ret = &mode_rtl;
550
break;
551
case Mode::Number::SMART_RTL:
552
ret = &mode_smartrtl;
553
break;
554
case Mode::Number::GUIDED:
555
ret = &mode_guided;
556
break;
557
case Mode::Number::INITIALISING:
558
ret = &mode_initializing;
559
break;
560
#if MODE_DOCK_ENABLED
561
case Mode::Number::DOCK:
562
ret = (Mode *)g2.mode_dock_ptr;
563
break;
564
#endif
565
default:
566
break;
567
}
568
return ret;
569
}
570
571