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_guided.cpp
Views: 1798
1
#include "Rover.h"
2
3
bool ModeGuided::_enter()
4
{
5
// initialise submode to stop or loiter
6
if (rover.is_boat()) {
7
if (!start_loiter()) {
8
start_stop();
9
}
10
} else {
11
start_stop();
12
}
13
14
// initialise waypoint navigation library
15
g2.wp_nav.init();
16
17
send_notification = false;
18
19
return true;
20
}
21
22
void ModeGuided::update()
23
{
24
switch (_guided_mode) {
25
case SubMode::WP:
26
{
27
// check if we've reached the destination
28
if (!g2.wp_nav.reached_destination()) {
29
// update navigation controller
30
navigate_to_waypoint();
31
} else {
32
// send notification
33
if (send_notification) {
34
send_notification = false;
35
rover.gcs().send_mission_item_reached_message(0);
36
}
37
38
// we have reached the destination so stay here
39
if (rover.is_boat()) {
40
if (!start_loiter()) {
41
stop_vehicle();
42
}
43
} else {
44
stop_vehicle();
45
}
46
// update distance to destination
47
_distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination());
48
}
49
break;
50
}
51
52
case SubMode::HeadingAndSpeed:
53
{
54
// stop vehicle if target not updated within 3 seconds
55
if (have_attitude_target && (millis() - _des_att_time_ms) > 3000) {
56
gcs().send_text(MAV_SEVERITY_WARNING, "target not received last 3secs, stopping");
57
have_attitude_target = false;
58
}
59
if (have_attitude_target) {
60
// run steering and throttle controllers
61
calc_steering_to_heading(_desired_yaw_cd);
62
calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);
63
} else {
64
// we have reached the destination so stay here
65
if (rover.is_boat()) {
66
if (!start_loiter()) {
67
stop_vehicle();
68
}
69
} else {
70
stop_vehicle();
71
}
72
}
73
break;
74
}
75
76
case SubMode::TurnRateAndSpeed:
77
{
78
// stop vehicle if target not updated within 3 seconds
79
if (have_attitude_target && (millis() - _des_att_time_ms) > 3000) {
80
gcs().send_text(MAV_SEVERITY_WARNING, "target not received last 3secs, stopping");
81
have_attitude_target = false;
82
}
83
if (have_attitude_target) {
84
// run steering and throttle controllers
85
float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds * 0.01f),
86
g2.motors.limit.steer_left,
87
g2.motors.limit.steer_right,
88
rover.G_Dt);
89
set_steering(steering_out * 4500.0f);
90
calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);
91
} else {
92
// we have reached the destination so stay here
93
if (rover.is_boat()) {
94
if (!start_loiter()) {
95
stop_vehicle();
96
}
97
} else {
98
stop_vehicle();
99
}
100
}
101
break;
102
}
103
104
case SubMode::Loiter:
105
{
106
rover.mode_loiter.update();
107
break;
108
}
109
110
case SubMode::SteeringAndThrottle:
111
{
112
// handle timeout
113
if (_have_strthr && (AP_HAL::millis() - _strthr_time_ms) > 3000) {
114
_have_strthr = false;
115
gcs().send_text(MAV_SEVERITY_WARNING, "target not received last 3secs, stopping");
116
}
117
if (_have_strthr) {
118
// pass latest steering and throttle directly to motors library
119
g2.motors.set_steering(_strthr_steering * 4500.0f, false);
120
g2.motors.set_throttle(_strthr_throttle * 100.0f);
121
} else {
122
// loiter or stop vehicle
123
if (rover.is_boat()) {
124
if (!start_loiter()) {
125
stop_vehicle();
126
}
127
} else {
128
stop_vehicle();
129
}
130
}
131
break;
132
}
133
134
case SubMode::Stop:
135
stop_vehicle();
136
break;
137
138
default:
139
gcs().send_text(MAV_SEVERITY_WARNING, "Unknown GUIDED mode");
140
break;
141
}
142
}
143
144
// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
145
float ModeGuided::wp_bearing() const
146
{
147
switch (_guided_mode) {
148
case SubMode::WP:
149
return g2.wp_nav.wp_bearing_cd() * 0.01f;
150
case SubMode::HeadingAndSpeed:
151
case SubMode::TurnRateAndSpeed:
152
return 0.0f;
153
case SubMode::Loiter:
154
return rover.mode_loiter.wp_bearing();
155
case SubMode::SteeringAndThrottle:
156
case SubMode::Stop:
157
return 0.0f;
158
}
159
160
// we should never reach here but just in case, return 0
161
return 0.0f;
162
}
163
164
float ModeGuided::nav_bearing() const
165
{
166
switch (_guided_mode) {
167
case SubMode::WP:
168
return g2.wp_nav.nav_bearing_cd() * 0.01f;
169
case SubMode::HeadingAndSpeed:
170
case SubMode::TurnRateAndSpeed:
171
return 0.0f;
172
case SubMode::Loiter:
173
return rover.mode_loiter.nav_bearing();
174
case SubMode::SteeringAndThrottle:
175
case SubMode::Stop:
176
return 0.0f;
177
}
178
179
// we should never reach here but just in case, return 0
180
return 0.0f;
181
}
182
183
float ModeGuided::crosstrack_error() const
184
{
185
switch (_guided_mode) {
186
case SubMode::WP:
187
return g2.wp_nav.crosstrack_error();
188
case SubMode::HeadingAndSpeed:
189
case SubMode::TurnRateAndSpeed:
190
return 0.0f;
191
case SubMode::Loiter:
192
return rover.mode_loiter.crosstrack_error();
193
case SubMode::SteeringAndThrottle:
194
case SubMode::Stop:
195
return 0.0f;
196
}
197
198
// we should never reach here but just in case, return 0
199
return 0.0f;
200
}
201
202
float ModeGuided::get_desired_lat_accel() const
203
{
204
switch (_guided_mode) {
205
case SubMode::WP:
206
return g2.wp_nav.get_lat_accel();
207
case SubMode::HeadingAndSpeed:
208
case SubMode::TurnRateAndSpeed:
209
return 0.0f;
210
case SubMode::Loiter:
211
return rover.mode_loiter.get_desired_lat_accel();
212
case SubMode::SteeringAndThrottle:
213
case SubMode::Stop:
214
return 0.0f;
215
}
216
217
// we should never reach here but just in case, return 0
218
return 0.0f;
219
}
220
221
// return distance (in meters) to destination
222
float ModeGuided::get_distance_to_destination() const
223
{
224
switch (_guided_mode) {
225
case SubMode::WP:
226
return _distance_to_destination;
227
case SubMode::HeadingAndSpeed:
228
case SubMode::TurnRateAndSpeed:
229
return 0.0f;
230
case SubMode::Loiter:
231
return rover.mode_loiter.get_distance_to_destination();
232
case SubMode::SteeringAndThrottle:
233
case SubMode::Stop:
234
return 0.0f;
235
}
236
237
// we should never reach here but just in case, return 0
238
return 0.0f;
239
}
240
241
// return true if vehicle has reached or even passed destination
242
bool ModeGuided::reached_destination() const
243
{
244
switch (_guided_mode) {
245
case SubMode::WP:
246
return g2.wp_nav.reached_destination();
247
case SubMode::HeadingAndSpeed:
248
case SubMode::TurnRateAndSpeed:
249
case SubMode::Loiter:
250
case SubMode::SteeringAndThrottle:
251
case SubMode::Stop:
252
return true;
253
}
254
255
// we should never reach here but just in case, return true is the safer option
256
return true;
257
}
258
259
// set desired speed in m/s
260
bool ModeGuided::set_desired_speed(float speed)
261
{
262
switch (_guided_mode) {
263
case SubMode::WP:
264
return g2.wp_nav.set_speed_max(speed);
265
case SubMode::HeadingAndSpeed:
266
case SubMode::TurnRateAndSpeed:
267
// speed is set from mavlink message
268
return false;
269
case SubMode::Loiter:
270
return rover.mode_loiter.set_desired_speed(speed);
271
case SubMode::SteeringAndThrottle:
272
case SubMode::Stop:
273
// no speed control
274
return false;
275
}
276
return false;
277
}
278
279
// get desired location
280
bool ModeGuided::get_desired_location(Location& destination) const
281
{
282
switch (_guided_mode) {
283
case SubMode::WP:
284
if (g2.wp_nav.is_destination_valid()) {
285
destination = g2.wp_nav.get_oa_destination();
286
return true;
287
}
288
return false;
289
case SubMode::HeadingAndSpeed:
290
case SubMode::TurnRateAndSpeed:
291
// not supported in these submodes
292
return false;
293
case SubMode::Loiter:
294
// get destination from loiter
295
return rover.mode_loiter.get_desired_location(destination);
296
case SubMode::SteeringAndThrottle:
297
case SubMode::Stop:
298
// no desired location in this submode
299
break;
300
}
301
302
// should never get here but just in case
303
return false;
304
}
305
306
// set desired location
307
bool ModeGuided::set_desired_location(const Location &destination, Location next_destination)
308
{
309
if (use_scurves_for_navigation()) {
310
// use scurves for navigation
311
if (!g2.wp_nav.set_desired_location(destination, next_destination)) {
312
return false;
313
}
314
} else {
315
// use position controller input shaping for navigation
316
// this does not support object avoidance but does allow faster updates of the target
317
if (!g2.wp_nav.set_desired_location_expect_fast_update(destination)) {
318
return false;
319
}
320
}
321
322
// handle guided specific initialisation and logging
323
_guided_mode = SubMode::WP;
324
send_notification = true;
325
#if HAL_LOGGING_ENABLED
326
rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f));
327
#endif
328
return true;
329
}
330
331
// set desired attitude
332
void ModeGuided::set_desired_heading_and_speed(float yaw_angle_cd, float target_speed)
333
{
334
// initialisation and logging
335
_guided_mode = SubMode::HeadingAndSpeed;
336
_des_att_time_ms = AP_HAL::millis();
337
338
// record targets
339
_desired_yaw_cd = yaw_angle_cd;
340
_desired_speed = target_speed;
341
have_attitude_target = true;
342
343
#if HAL_LOGGING_ENABLED
344
// log new target
345
rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_cd, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f));
346
#endif
347
}
348
349
void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed)
350
{
351
// handle initialisation
352
if (_guided_mode != SubMode::HeadingAndSpeed) {
353
_guided_mode = SubMode::HeadingAndSpeed;
354
_desired_yaw_cd = ahrs.yaw_sensor;
355
}
356
set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd + yaw_delta_cd), target_speed);
357
}
358
359
// set desired velocity
360
void ModeGuided::set_desired_turn_rate_and_speed(float turn_rate_cds, float target_speed)
361
{
362
// handle initialisation
363
_guided_mode = SubMode::TurnRateAndSpeed;
364
_des_att_time_ms = AP_HAL::millis();
365
366
// record targets
367
_desired_yaw_rate_cds = turn_rate_cds;
368
_desired_speed = target_speed;
369
have_attitude_target = true;
370
371
#if HAL_LOGGING_ENABLED
372
// log new target
373
rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_rate_cds, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f));
374
#endif
375
}
376
377
// set steering and throttle (both in the range -1 to +1)
378
void ModeGuided::set_steering_and_throttle(float steering, float throttle)
379
{
380
_guided_mode = SubMode::SteeringAndThrottle;
381
_strthr_time_ms = AP_HAL::millis();
382
_strthr_steering = constrain_float(steering, -1.0f, 1.0f);
383
_strthr_throttle = constrain_float(throttle, -1.0f, 1.0f);
384
_have_strthr = true;
385
}
386
387
bool ModeGuided::start_loiter()
388
{
389
if (rover.mode_loiter.enter()) {
390
_guided_mode = SubMode::Loiter;
391
return true;
392
}
393
return false;
394
}
395
396
397
// start stopping vehicle as quickly as possible
398
void ModeGuided::start_stop()
399
{
400
_guided_mode = SubMode::Stop;
401
}
402
403
// set guided timeout and movement limits
404
void ModeGuided::limit_set(uint32_t timeout_ms, float horiz_max)
405
{
406
limit.timeout_ms = timeout_ms;
407
limit.horiz_max = horiz_max;
408
}
409
410
// clear/turn off guided limits
411
void ModeGuided::limit_clear()
412
{
413
limit.timeout_ms = 0;
414
limit.horiz_max = 0.0f;
415
}
416
417
// initialise guided start time and location as reference for limit checking
418
// only called from AUTO mode's start_guided method
419
void ModeGuided::limit_init_time_and_location()
420
{
421
limit.start_time_ms = AP_HAL::millis();
422
limit.start_loc = rover.current_loc;
423
}
424
425
// returns true if guided mode has breached a limit
426
bool ModeGuided::limit_breached() const
427
{
428
// check if we have passed the timeout
429
if ((limit.timeout_ms > 0) && (millis() - limit.start_time_ms >= limit.timeout_ms)) {
430
return true;
431
}
432
433
// check if we have gone beyond horizontal limit
434
if (is_positive(limit.horiz_max)) {
435
return (rover.current_loc.get_distance(limit.start_loc) > limit.horiz_max);
436
}
437
438
// if we got this far we must be within limits
439
return false;
440
}
441
442
// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping
443
// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping)
444
bool ModeGuided::use_scurves_for_navigation() const
445
{
446
return ((g2.guided_options.get() & uint32_t(Options::SCurvesUsedForNavigation)) != 0);
447
}
448
449