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