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/ArduSub/mode_guided.cpp
Views: 1798
1
#include "Sub.h"
2
3
/*
4
* Init and run calls for guided flight mode
5
*/
6
7
#define GUIDED_POSVEL_TIMEOUT_MS 3000 // guided mode's position-velocity controller times out after 3seconds with no new updates
8
#define GUIDED_ATTITUDE_TIMEOUT_MS 1000 // guided mode's attitude controller times out after 1 second with no new updates
9
10
static Vector3p posvel_pos_target_cm;
11
static Vector3f posvel_vel_target_cms;
12
static uint32_t update_time_ms;
13
14
struct {
15
uint32_t update_time_ms;
16
float roll_cd;
17
float pitch_cd;
18
float yaw_cd;
19
float climb_rate_cms;
20
} static guided_angle_state = {0,0.0f, 0.0f, 0.0f, 0.0f};
21
22
struct Guided_Limit {
23
uint32_t timeout_ms; // timeout (in seconds) from the time that guided is invoked
24
float alt_min_cm; // lower altitude limit in cm above home (0 = no limit)
25
float alt_max_cm; // upper altitude limit in cm above home (0 = no limit)
26
float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit)
27
uint32_t start_time;// system time in milliseconds that control was handed to the external computer
28
Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit
29
} guided_limit;
30
31
// guided_init - initialise guided controller
32
bool ModeGuided::init(bool ignore_checks)
33
{
34
if (!sub.position_ok() && !ignore_checks) {
35
return false;
36
}
37
38
// start in position control mode
39
guided_pos_control_start();
40
return true;
41
}
42
43
// get_default_auto_yaw_mode - returns auto_yaw_mode based on WP_YAW_BEHAVIOR parameter
44
// set rtl parameter to true if this is during an RTL
45
autopilot_yaw_mode ModeGuided::get_default_auto_yaw_mode(bool rtl) const
46
{
47
switch (g.wp_yaw_behavior) {
48
49
case WP_YAW_BEHAVIOR_NONE:
50
return AUTO_YAW_HOLD;
51
break;
52
53
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL:
54
if (rtl) {
55
return AUTO_YAW_HOLD;
56
} else {
57
return AUTO_YAW_LOOK_AT_NEXT_WP;
58
}
59
break;
60
61
case WP_YAW_BEHAVIOR_LOOK_AHEAD:
62
return AUTO_YAW_LOOK_AHEAD;
63
break;
64
65
case WP_YAW_BEHAVIOR_CORRECT_XTRACK:
66
return AUTO_YAW_CORRECT_XTRACK;
67
break;
68
69
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP:
70
default:
71
return AUTO_YAW_LOOK_AT_NEXT_WP;
72
break;
73
}
74
}
75
76
77
// initialise guided mode's position controller
78
void ModeGuided::guided_pos_control_start()
79
{
80
// set to position control mode
81
sub.guided_mode = Guided_WP;
82
83
// initialise waypoint controller
84
sub.wp_nav.wp_and_spline_init();
85
86
// initialise wpnav to stopping point at current altitude
87
// To-Do: set to current location if disarmed?
88
// To-Do: set to stopping point altitude?
89
Vector3f stopping_point;
90
sub.wp_nav.get_wp_stopping_point(stopping_point);
91
92
// no need to check return status because terrain data is not used
93
sub.wp_nav.set_wp_destination(stopping_point, false);
94
95
// initialise yaw
96
sub.yaw_rate_only = false;
97
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
98
}
99
100
// initialise guided mode's velocity controller
101
void ModeGuided::guided_vel_control_start()
102
{
103
// set guided_mode to velocity controller
104
sub.guided_mode = Guided_Velocity;
105
106
// initialize vertical maximum speeds and acceleration
107
position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
108
position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
109
110
// initialise velocity controller
111
position_control->init_z_controller();
112
position_control->init_xy_controller();
113
114
// pilot always controls yaw
115
sub.yaw_rate_only = false;
116
set_auto_yaw_mode(AUTO_YAW_HOLD);
117
}
118
119
// initialise guided mode's posvel controller
120
void ModeGuided::guided_posvel_control_start()
121
{
122
// set guided_mode to velocity controller
123
sub.guided_mode = Guided_PosVel;
124
125
// set vertical speed and acceleration
126
position_control->set_max_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());
127
position_control->set_correction_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());
128
129
// initialise velocity controller
130
position_control->init_z_controller();
131
position_control->init_xy_controller();
132
133
// pilot always controls yaw
134
sub.yaw_rate_only = false;
135
set_auto_yaw_mode(AUTO_YAW_HOLD);
136
}
137
138
// initialise guided mode's angle controller
139
void ModeGuided::guided_angle_control_start()
140
{
141
// set guided_mode to velocity controller
142
sub.guided_mode = Guided_Angle;
143
144
// set vertical speed and acceleration
145
position_control->set_max_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());
146
position_control->set_correction_speed_accel_z(sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up(), sub.wp_nav.get_accel_z());
147
148
// initialise velocity controller
149
position_control->init_z_controller();
150
151
// initialise targets
152
guided_angle_state.update_time_ms = AP_HAL::millis();
153
guided_angle_state.roll_cd = ahrs.roll_sensor;
154
guided_angle_state.pitch_cd = ahrs.pitch_sensor;
155
guided_angle_state.yaw_cd = ahrs.yaw_sensor;
156
guided_angle_state.climb_rate_cms = 0.0f;
157
158
// pilot always controls yaw
159
sub.yaw_rate_only = false;
160
set_auto_yaw_mode(AUTO_YAW_HOLD);
161
}
162
163
// guided_set_destination - sets guided mode's target destination
164
// Returns true if the fence is enabled and guided waypoint is within the fence
165
// else return false if the waypoint is outside the fence
166
bool ModeGuided::guided_set_destination(const Vector3f& destination)
167
{
168
#if AP_FENCE_ENABLED
169
// reject destination if outside the fence
170
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
171
if (!sub.fence.check_destination_within_fence(dest_loc)) {
172
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
173
// failure is propagated to GCS with NAK
174
return false;
175
}
176
#endif
177
178
// ensure we are in position control mode
179
if (sub.guided_mode != Guided_WP) {
180
guided_pos_control_start();
181
}
182
183
// no need to check return status because terrain data is not used
184
sub.wp_nav.set_wp_destination(destination, false);
185
186
#if HAL_LOGGING_ENABLED
187
// log target
188
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f());
189
#endif
190
191
return true;
192
}
193
194
// sets guided mode's target from a Location object
195
// returns false if destination could not be set (probably caused by missing terrain data)
196
// or if the fence is enabled and guided waypoint is outside the fence
197
bool ModeGuided::guided_set_destination(const Location& dest_loc)
198
{
199
#if AP_FENCE_ENABLED
200
// reject destination outside the fence.
201
// Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails
202
if (!sub.fence.check_destination_within_fence(dest_loc)) {
203
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
204
// failure is propagated to GCS with NAK
205
return false;
206
}
207
#endif
208
209
// ensure we are in position control mode
210
if (sub.guided_mode != Guided_WP) {
211
guided_pos_control_start();
212
}
213
214
if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) {
215
// failure to set destination can only be because of missing terrain data
216
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
217
// failure is propagated to GCS with NAK
218
return false;
219
}
220
221
#if HAL_LOGGING_ENABLED
222
// log target
223
sub.Log_Write_GuidedTarget(sub.guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f());
224
#endif
225
226
return true;
227
}
228
229
// guided_set_destination - sets guided mode's target destination and target heading
230
// Returns true if the fence is enabled and guided waypoint is within the fence
231
// else return false if the waypoint is outside the fence
232
bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
233
{
234
#if AP_FENCE_ENABLED
235
// reject destination if outside the fence
236
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
237
if (!sub.fence.check_destination_within_fence(dest_loc)) {
238
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
239
// failure is propagated to GCS with NAK
240
return false;
241
}
242
#endif
243
244
// ensure we are in position control mode
245
if (sub.guided_mode != Guided_WP) {
246
guided_pos_control_start();
247
}
248
249
// set yaw state
250
guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
251
252
update_time_ms = AP_HAL::millis();
253
254
// no need to check return status because terrain data is not used
255
sub.wp_nav.set_wp_destination(destination, false);
256
257
#if HAL_LOGGING_ENABLED
258
// log target
259
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f());
260
#endif
261
262
return true;
263
}
264
265
// guided_set_velocity - sets guided mode's target velocity
266
void ModeGuided::guided_set_velocity(const Vector3f& velocity)
267
{
268
// check we are in velocity control mode
269
if (sub.guided_mode != Guided_Velocity) {
270
guided_vel_control_start();
271
}
272
273
update_time_ms = AP_HAL::millis();
274
275
// set position controller velocity target
276
position_control->set_vel_desired_cms(velocity);
277
}
278
279
// guided_set_velocity - sets guided mode's target velocity
280
void ModeGuided::guided_set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
281
{
282
// check we are in velocity control mode
283
if (sub.guided_mode != Guided_Velocity) {
284
guided_vel_control_start();
285
}
286
287
// set yaw state
288
guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
289
290
update_time_ms = AP_HAL::millis();
291
292
// set position controller velocity target
293
position_control->set_vel_desired_cms(velocity);
294
295
}
296
297
// set guided mode posvel target
298
bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity)
299
{
300
#if AP_FENCE_ENABLED
301
// reject destination if outside the fence
302
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
303
if (!sub.fence.check_destination_within_fence(dest_loc)) {
304
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
305
// failure is propagated to GCS with NAK
306
return false;
307
}
308
#endif
309
310
// check we are in posvel control mode
311
if (sub.guided_mode != Guided_PosVel) {
312
guided_posvel_control_start();
313
}
314
315
update_time_ms = AP_HAL::millis();
316
posvel_pos_target_cm = destination.topostype();
317
posvel_vel_target_cms = velocity;
318
319
position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());
320
float dz = posvel_pos_target_cm.z;
321
position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0);
322
posvel_pos_target_cm.z = dz;
323
324
#if HAL_LOGGING_ENABLED
325
// log target
326
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity);
327
#endif
328
329
return true;
330
}
331
332
// set guided mode posvel target
333
bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw)
334
{
335
#if AP_FENCE_ENABLED
336
// reject destination if outside the fence
337
const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN);
338
if (!sub.fence.check_destination_within_fence(dest_loc)) {
339
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
340
// failure is propagated to GCS with NAK
341
return false;
342
}
343
#endif
344
345
// check we are in posvel control mode
346
if (sub.guided_mode != Guided_PosVel) {
347
guided_posvel_control_start();
348
}
349
350
// set yaw state
351
guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw);
352
353
update_time_ms = AP_HAL::millis();
354
355
posvel_pos_target_cm = destination.topostype();
356
posvel_vel_target_cms = velocity;
357
358
position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());
359
float dz = posvel_pos_target_cm.z;
360
position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0);
361
posvel_pos_target_cm.z = dz;
362
363
#if HAL_LOGGING_ENABLED
364
// log target
365
sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity);
366
#endif
367
368
return true;
369
}
370
371
// set guided mode angle target
372
void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms)
373
{
374
// check we are in angle control mode
375
if (sub.guided_mode != Guided_Angle) {
376
guided_angle_control_start();
377
}
378
379
// convert quaternion to euler angles
380
q.to_euler(guided_angle_state.roll_cd, guided_angle_state.pitch_cd, guided_angle_state.yaw_cd);
381
guided_angle_state.roll_cd = ToDeg(guided_angle_state.roll_cd) * 100.0f;
382
guided_angle_state.pitch_cd = ToDeg(guided_angle_state.pitch_cd) * 100.0f;
383
guided_angle_state.yaw_cd = wrap_180_cd(ToDeg(guided_angle_state.yaw_cd) * 100.0f);
384
385
guided_angle_state.climb_rate_cms = climb_rate_cms;
386
guided_angle_state.update_time_ms = AP_HAL::millis();
387
}
388
389
// helper function to set yaw state and targets
390
void ModeGuided::guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
391
{
392
float current_yaw = wrap_2PI(AP::ahrs().get_yaw());
393
float euler_yaw_angle;
394
float yaw_error;
395
396
euler_yaw_angle = wrap_2PI((yaw_cd * 0.01f));
397
yaw_error = wrap_PI(euler_yaw_angle - current_yaw);
398
399
int direction = 0;
400
if (yaw_error < 0){
401
direction = -1;
402
} else {
403
direction = 1;
404
}
405
406
/*
407
case 1: target yaw only
408
case 2: target yaw and yaw rate
409
case 3: target yaw rate only
410
case 4: hold current yaw
411
*/
412
if (use_yaw && !use_yaw_rate) {
413
sub.yaw_rate_only = false;
414
sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, 0.0f, direction, relative_angle);
415
} else if (use_yaw && use_yaw_rate) {
416
sub.yaw_rate_only = false;
417
sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, yaw_rate_cds * 0.01f, direction, relative_angle);
418
} else if (!use_yaw && use_yaw_rate) {
419
sub.yaw_rate_only = true;
420
sub.mode_auto.set_yaw_rate(yaw_rate_cds * 0.01f);
421
} else{
422
sub.yaw_rate_only = false;
423
set_auto_yaw_mode(AUTO_YAW_HOLD);
424
}
425
}
426
427
// guided_run - runs the guided controller
428
// should be called at 100hz or more
429
void ModeGuided::run()
430
{
431
// call the correct auto controller
432
switch (sub.guided_mode) {
433
434
case Guided_WP:
435
// run position controller
436
guided_pos_control_run();
437
break;
438
439
case Guided_Velocity:
440
// run velocity controller
441
guided_vel_control_run();
442
break;
443
444
case Guided_PosVel:
445
// run position-velocity controller
446
guided_posvel_control_run();
447
break;
448
449
case Guided_Angle:
450
// run angle controller
451
guided_angle_control_run();
452
break;
453
}
454
}
455
456
// guided_pos_control_run - runs the guided position controller
457
// called from guided_run
458
void ModeGuided::guided_pos_control_run()
459
{
460
// if motors not enabled set throttle to zero and exit immediately
461
if (!motors.armed()) {
462
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
463
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
464
attitude_control->set_throttle_out(0,true,g.throttle_filt);
465
attitude_control->relax_attitude_controllers();
466
sub.wp_nav.wp_and_spline_init();
467
return;
468
}
469
470
// process pilot's yaw input
471
float target_yaw_rate = 0;
472
if (!sub.failsafe.pilot_input) {
473
// get pilot's desired yaw rate
474
target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
475
if (!is_zero(target_yaw_rate)) {
476
set_auto_yaw_mode(AUTO_YAW_HOLD);
477
} else{
478
if (sub.yaw_rate_only){
479
set_auto_yaw_mode(AUTO_YAW_RATE);
480
} else{
481
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
482
}
483
}
484
}
485
486
// set motors to full range
487
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
488
489
// run waypoint controller
490
sub.failsafe_terrain_set_status(sub.wp_nav.update_wpnav());
491
492
float lateral_out, forward_out;
493
sub.translate_wpnav_rp(lateral_out, forward_out);
494
495
// Send to forward/lateral outputs
496
motors.set_lateral(lateral_out);
497
motors.set_forward(forward_out);
498
499
// WP_Nav has set the vertical position control targets
500
// run the vertical position controller and set output throttle
501
position_control->update_z_controller();
502
503
// call attitude controller
504
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
505
// roll & pitch & yaw rate from pilot
506
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
507
} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {
508
// roll, pitch from pilot, yaw & yaw_rate from auto_control
509
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
510
attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);
511
} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {
512
// roll, pitch from pilot, yaw_rate from auto_control
513
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
514
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
515
} else {
516
// roll, pitch from pilot, yaw heading from auto_heading()
517
attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
518
}
519
}
520
521
// guided_vel_control_run - runs the guided velocity controller
522
// called from guided_run
523
void ModeGuided::guided_vel_control_run()
524
{
525
// ifmotors not enabled set throttle to zero and exit immediately
526
if (!motors.armed()) {
527
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
528
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
529
attitude_control->set_throttle_out(0,true,g.throttle_filt);
530
attitude_control->relax_attitude_controllers();
531
// initialise velocity controller
532
position_control->init_z_controller();
533
position_control->init_xy_controller();
534
return;
535
}
536
537
// process pilot's yaw input
538
float target_yaw_rate = 0;
539
if (!sub.failsafe.pilot_input) {
540
// get pilot's desired yaw rate
541
target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
542
if (!is_zero(target_yaw_rate)) {
543
set_auto_yaw_mode(AUTO_YAW_HOLD);
544
} else{
545
if (sub.yaw_rate_only){
546
set_auto_yaw_mode(AUTO_YAW_RATE);
547
} else{
548
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
549
}
550
}
551
}
552
553
// set motors to full range
554
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
555
556
// set velocity to zero if no updates received for 3 seconds
557
uint32_t tnow = AP_HAL::millis();
558
if (tnow - update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !position_control->get_vel_desired_cms().is_zero()) {
559
position_control->set_vel_desired_cms(Vector3f(0,0,0));
560
}
561
562
position_control->stop_pos_xy_stabilisation();
563
// call velocity controller which includes z axis controller
564
position_control->update_xy_controller();
565
566
position_control->set_pos_target_z_from_climb_rate_cm(position_control->get_vel_desired_cms().z);
567
position_control->update_z_controller();
568
569
float lateral_out, forward_out;
570
sub.translate_pos_control_rp(lateral_out, forward_out);
571
572
// Send to forward/lateral outputs
573
motors.set_lateral(lateral_out);
574
motors.set_forward(forward_out);
575
576
// call attitude controller
577
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
578
// roll & pitch & yaw rate from pilot
579
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
580
} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {
581
// roll, pitch from pilot, yaw & yaw_rate from auto_control
582
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
583
attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);
584
} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {
585
// roll, pitch from pilot, yaw_rate from auto_control
586
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
587
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
588
} else {
589
// roll, pitch from pilot, yaw heading from auto_heading()
590
attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
591
}
592
}
593
594
// guided_posvel_control_run - runs the guided posvel controller
595
// called from guided_run
596
void ModeGuided::guided_posvel_control_run()
597
{
598
// if motors not enabled set throttle to zero and exit immediately
599
if (!motors.armed()) {
600
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
601
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
602
attitude_control->set_throttle_out(0,true,g.throttle_filt);
603
attitude_control->relax_attitude_controllers();
604
// initialise velocity controller
605
position_control->init_z_controller();
606
position_control->init_xy_controller();
607
return;
608
}
609
610
// process pilot's yaw input
611
float target_yaw_rate = 0;
612
613
if (!sub.failsafe.pilot_input) {
614
// get pilot's desired yaw rate
615
target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
616
if (!is_zero(target_yaw_rate)) {
617
set_auto_yaw_mode(AUTO_YAW_HOLD);
618
} else{
619
if (sub.yaw_rate_only){
620
set_auto_yaw_mode(AUTO_YAW_RATE);
621
} else{
622
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
623
}
624
}
625
}
626
627
// set motors to full range
628
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
629
630
// set velocity to zero if no updates received for 3 seconds
631
uint32_t tnow = AP_HAL::millis();
632
if (tnow - update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !posvel_vel_target_cms.is_zero()) {
633
posvel_vel_target_cms.zero();
634
}
635
636
// advance position target using velocity target
637
posvel_pos_target_cm += (posvel_vel_target_cms * position_control->get_dt()).topostype();
638
639
// send position and velocity targets to position controller
640
position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f());
641
float pz = posvel_pos_target_cm.z;
642
position_control->input_pos_vel_accel_z(pz, posvel_vel_target_cms.z, 0);
643
posvel_pos_target_cm.z = pz;
644
645
// run position controller
646
position_control->update_xy_controller();
647
position_control->update_z_controller();
648
649
float lateral_out, forward_out;
650
sub.translate_pos_control_rp(lateral_out, forward_out);
651
652
// Send to forward/lateral outputs
653
motors.set_lateral(lateral_out);
654
motors.set_forward(forward_out);
655
656
// call attitude controller
657
if (sub.auto_yaw_mode == AUTO_YAW_HOLD) {
658
// roll & pitch & yaw rate from pilot
659
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
660
} else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) {
661
// roll, pitch from pilot, yaw & yaw_rate from auto_control
662
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
663
attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate);
664
} else if (sub.auto_yaw_mode == AUTO_YAW_RATE) {
665
// roll, pitch from pilot, and yaw_rate from auto_control
666
target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0;
667
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
668
} else {
669
// roll, pitch from pilot, yaw heading from auto_heading()
670
attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
671
}
672
}
673
674
// guided_angle_control_run - runs the guided angle controller
675
// called from guided_run
676
void ModeGuided::guided_angle_control_run()
677
{
678
// if motors not enabled set throttle to zero and exit immediately
679
if (!motors.armed()) {
680
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
681
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
682
attitude_control->set_throttle_out(0.0f,true,g.throttle_filt);
683
attitude_control->relax_attitude_controllers();
684
// initialise velocity controller
685
position_control->init_z_controller();
686
return;
687
}
688
689
// constrain desired lean angles
690
float roll_in = guided_angle_state.roll_cd;
691
float pitch_in = guided_angle_state.pitch_cd;
692
float total_in = norm(roll_in, pitch_in);
693
float angle_max = MIN(attitude_control->get_althold_lean_angle_max_cd(), sub.aparm.angle_max);
694
if (total_in > angle_max) {
695
float ratio = angle_max / total_in;
696
roll_in *= ratio;
697
pitch_in *= ratio;
698
}
699
700
// wrap yaw request
701
float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd);
702
703
// constrain climb rate
704
float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -sub.wp_nav.get_default_speed_down(), sub.wp_nav.get_default_speed_up());
705
706
// check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
707
uint32_t tnow = AP_HAL::millis();
708
if (tnow - guided_angle_state.update_time_ms > GUIDED_ATTITUDE_TIMEOUT_MS) {
709
roll_in = 0.0f;
710
pitch_in = 0.0f;
711
climb_rate_cms = 0.0f;
712
}
713
714
// set motors to full range
715
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
716
717
// call attitude controller
718
attitude_control->input_euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true);
719
720
// call position controller
721
position_control->set_pos_target_z_from_climb_rate_cm(climb_rate_cms);
722
position_control->update_z_controller();
723
}
724
725
// Guided Limit code
726
727
// guided_limit_clear - clear/turn off guided limits
728
void ModeGuided::guided_limit_clear()
729
{
730
guided_limit.timeout_ms = 0;
731
guided_limit.alt_min_cm = 0.0f;
732
guided_limit.alt_max_cm = 0.0f;
733
guided_limit.horiz_max_cm = 0.0f;
734
}
735
736
737
// set_auto_yaw_mode - sets the yaw mode for auto
738
void ModeGuided::set_auto_yaw_mode(autopilot_yaw_mode yaw_mode)
739
{
740
// return immediately if no change
741
if (sub.auto_yaw_mode == yaw_mode) {
742
return;
743
}
744
sub.auto_yaw_mode = yaw_mode;
745
746
// perform initialisation
747
switch (sub.auto_yaw_mode) {
748
749
case AUTO_YAW_HOLD:
750
// pilot controls the heading
751
break;
752
753
case AUTO_YAW_LOOK_AT_NEXT_WP:
754
// wpnav will initialise heading when wpnav's set_destination method is called
755
break;
756
757
case AUTO_YAW_ROI:
758
// point towards a location held in yaw_look_at_WP
759
sub.yaw_look_at_WP_bearing = ahrs.yaw_sensor;
760
break;
761
762
case AUTO_YAW_LOOK_AT_HEADING:
763
// keep heading pointing in the direction held in yaw_look_at_heading
764
// caller should set the yaw_look_at_heading
765
break;
766
767
case AUTO_YAW_LOOK_AHEAD:
768
// Commanded Yaw to automatically look ahead.
769
sub.yaw_look_ahead_bearing = ahrs.yaw_sensor;
770
break;
771
772
case AUTO_YAW_RESETTOARMEDYAW:
773
// initial_armed_bearing will be set during arming so no init required
774
break;
775
776
case AUTO_YAW_RATE:
777
// set target yaw rate to yaw_look_at_heading_slew
778
break;
779
}
780
}
781
782
// get_auto_heading - returns target heading depending upon auto_yaw_mode
783
// 100hz update rate
784
float ModeGuided::get_auto_heading()
785
{
786
switch (sub.auto_yaw_mode) {
787
788
case AUTO_YAW_ROI:
789
// point towards a location held in roi_WP
790
return sub.get_roi_yaw();
791
break;
792
793
case AUTO_YAW_LOOK_AT_HEADING:
794
// keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed
795
return sub.yaw_look_at_heading;
796
break;
797
798
case AUTO_YAW_LOOK_AHEAD:
799
// Commanded Yaw to automatically look ahead.
800
return sub.get_look_ahead_yaw();
801
break;
802
803
case AUTO_YAW_RESETTOARMEDYAW:
804
// changes yaw to be same as when quad was armed
805
return sub.initial_armed_bearing;
806
break;
807
808
case AUTO_YAW_CORRECT_XTRACK: {
809
// TODO return current yaw if not in appropriate mode
810
// Bearing of current track (centidegrees)
811
float track_bearing = get_bearing_cd(sub.wp_nav.get_wp_origin().xy(), sub.wp_nav.get_wp_destination().xy());
812
813
// Bearing from current position towards intermediate position target (centidegrees)
814
const Vector2f target_vel_xy = position_control->get_vel_target_cms().xy();
815
float angle_error = 0.0f;
816
if (target_vel_xy.length() >= position_control->get_max_speed_xy_cms() * 0.1f) {
817
const float desired_angle_cd = degrees(target_vel_xy.angle()) * 100.0f;
818
angle_error = wrap_180_cd(desired_angle_cd - track_bearing);
819
}
820
float angle_limited = constrain_float(angle_error, -g.xtrack_angle_limit * 100.0f, g.xtrack_angle_limit * 100.0f);
821
return wrap_360_cd(track_bearing + angle_limited);
822
}
823
break;
824
825
case AUTO_YAW_LOOK_AT_NEXT_WP:
826
default:
827
// point towards next waypoint.
828
// we don't use wp_bearing because we don't want the vehicle to turn too much during flight
829
return sub.wp_nav.get_yaw();
830
break;
831
}
832
}
833
// guided_limit_set - set guided timeout and movement limits
834
void ModeGuided::guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm)
835
{
836
guided_limit.timeout_ms = timeout_ms;
837
guided_limit.alt_min_cm = alt_min_cm;
838
guided_limit.alt_max_cm = alt_max_cm;
839
guided_limit.horiz_max_cm = horiz_max_cm;
840
}
841
842
// guided_limit_init_time_and_pos - initialise guided start time and position as reference for limit checking
843
// only called from AUTO mode's auto_nav_guided_start function
844
void ModeGuided::guided_limit_init_time_and_pos()
845
{
846
// initialise start time
847
guided_limit.start_time = AP_HAL::millis();
848
849
// initialise start position from current position
850
guided_limit.start_pos = inertial_nav.get_position_neu_cm();
851
}
852
853
// guided_limit_check - returns true if guided mode has breached a limit
854
// used when guided is invoked from the NAV_GUIDED_ENABLE mission command
855
bool ModeGuided::guided_limit_check()
856
{
857
// check if we have passed the timeout
858
if ((guided_limit.timeout_ms > 0) && (AP_HAL::millis() - guided_limit.start_time >= guided_limit.timeout_ms)) {
859
return true;
860
}
861
862
// get current location
863
const Vector3f& curr_pos = inertial_nav.get_position_neu_cm();
864
865
// check if we have gone below min alt
866
if (!is_zero(guided_limit.alt_min_cm) && (curr_pos.z < guided_limit.alt_min_cm)) {
867
return true;
868
}
869
870
// check if we have gone above max alt
871
if (!is_zero(guided_limit.alt_max_cm) && (curr_pos.z > guided_limit.alt_max_cm)) {
872
return true;
873
}
874
875
// check if we have gone beyond horizontal limit
876
if (guided_limit.horiz_max_cm > 0.0f) {
877
const float horiz_move = get_horizontal_distance_cm(guided_limit.start_pos.xy(), curr_pos.xy());
878
if (horiz_move > guided_limit.horiz_max_cm) {
879
return true;
880
}
881
}
882
883
// if we got this far we must be within limits
884
return false;
885
}
886
887