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/commands_logic.cpp
Views: 1798
1
#include "Sub.h"
2
3
#include <AP_RTC/AP_RTC.h>
4
5
static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
6
7
// start_command - this function will be called when the ap_mission lib wishes to start a new command
8
bool Sub::start_command(const AP_Mission::Mission_Command& cmd)
9
{
10
const Location &target_loc = cmd.content.location;
11
auto alt_frame = target_loc.get_alt_frame();
12
13
if (alt_frame == Location::AltFrame::ABOVE_HOME) {
14
if (target_loc.alt > 0) {
15
gcs().send_text(MAV_SEVERITY_WARNING, "Alt above home must be negative");
16
return false;
17
}
18
} else if (alt_frame == Location::AltFrame::ABOVE_TERRAIN) {
19
if (target_loc.alt < 0) {
20
gcs().send_text(MAV_SEVERITY_WARNING, "Alt above terrain must be positive");
21
return false;
22
}
23
} else {
24
gcs().send_text(MAV_SEVERITY_WARNING, "Bad alt frame");
25
return false;
26
}
27
28
switch (cmd.id) {
29
30
///
31
/// navigation commands
32
///
33
case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint
34
do_nav_wp(cmd);
35
break;
36
37
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
38
do_surface(cmd);
39
break;
40
41
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
42
do_RTL();
43
break;
44
45
case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely
46
do_loiter_unlimited(cmd);
47
break;
48
49
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
50
do_circle(cmd);
51
break;
52
53
case MAV_CMD_NAV_LOITER_TIME: // 19
54
do_loiter_time(cmd);
55
break;
56
57
#if NAV_GUIDED
58
case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer
59
do_nav_guided_enable(cmd);
60
break;
61
#endif
62
63
case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command
64
do_nav_delay(cmd);
65
break;
66
67
//
68
// conditional commands
69
//
70
case MAV_CMD_CONDITION_DELAY: // 112
71
do_wait_delay(cmd);
72
break;
73
74
case MAV_CMD_CONDITION_DISTANCE: // 114
75
do_within_distance(cmd);
76
break;
77
78
case MAV_CMD_CONDITION_YAW: // 115
79
do_yaw(cmd);
80
break;
81
82
///
83
/// do commands
84
///
85
case MAV_CMD_DO_CHANGE_SPEED: // 178
86
do_change_speed(cmd);
87
break;
88
89
case MAV_CMD_DO_SET_HOME: // 179
90
do_set_home(cmd);
91
break;
92
93
case MAV_CMD_DO_SET_ROI: // 201
94
// point the vehicle and camera at a region of interest (ROI)
95
do_roi(cmd);
96
break;
97
98
case MAV_CMD_DO_MOUNT_CONTROL: // 205
99
// point the camera to a specified angle
100
do_mount_control(cmd);
101
break;
102
103
#if NAV_GUIDED
104
case MAV_CMD_DO_GUIDED_LIMITS: // 222 accept guided mode limits
105
do_guided_limits(cmd);
106
break;
107
#endif
108
109
default:
110
// unable to use the command, allow the vehicle to try the next command
111
gcs().send_text(MAV_SEVERITY_WARNING, "Ignoring command %d", cmd.id);
112
return false;
113
}
114
115
// always return success
116
return true;
117
}
118
119
/********************************************************************************/
120
// Verify command Handlers
121
/********************************************************************************/
122
123
// check to see if current command goal has been achieved
124
// called by mission library in mission.update()
125
bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)
126
{
127
if (control_mode == Mode::Number::AUTO) {
128
bool cmd_complete = verify_command(cmd);
129
130
// send message to GCS
131
if (cmd_complete) {
132
gcs().send_mission_item_reached_message(cmd.index);
133
}
134
135
return cmd_complete;
136
}
137
return false;
138
}
139
140
141
// check if current mission command has completed
142
bool Sub::verify_command(const AP_Mission::Mission_Command& cmd)
143
{
144
switch (cmd.id) {
145
//
146
// navigation commands
147
//
148
case MAV_CMD_NAV_WAYPOINT:
149
return verify_nav_wp(cmd);
150
151
case MAV_CMD_NAV_LAND:
152
return verify_surface(cmd);
153
154
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
155
return verify_RTL();
156
157
case MAV_CMD_NAV_LOITER_UNLIM:
158
return verify_loiter_unlimited();
159
160
case MAV_CMD_NAV_LOITER_TURNS:
161
return verify_circle(cmd);
162
163
case MAV_CMD_NAV_LOITER_TIME:
164
return verify_loiter_time();
165
166
#if NAV_GUIDED
167
case MAV_CMD_NAV_GUIDED_ENABLE:
168
return verify_nav_guided_enable(cmd);
169
#endif
170
171
case MAV_CMD_NAV_DELAY:
172
return verify_nav_delay(cmd);
173
174
///
175
/// conditional commands
176
///
177
case MAV_CMD_CONDITION_DELAY:
178
return verify_wait_delay();
179
180
case MAV_CMD_CONDITION_DISTANCE:
181
return verify_within_distance();
182
183
case MAV_CMD_CONDITION_YAW:
184
return verify_yaw();
185
186
// do commands (always return true)
187
case MAV_CMD_DO_CHANGE_SPEED:
188
case MAV_CMD_DO_SET_HOME:
189
case MAV_CMD_DO_SET_ROI:
190
case MAV_CMD_DO_MOUNT_CONTROL:
191
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
192
case MAV_CMD_DO_GUIDED_LIMITS:
193
return true;
194
195
default:
196
// error message
197
gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
198
// return true if we do not recognize the command so that we move on to the next command
199
return true;
200
}
201
}
202
203
// exit_mission - function that is called once the mission completes
204
void Sub::exit_mission()
205
{
206
// play a tone
207
AP_Notify::events.mission_complete = 1;
208
209
// Try to enter loiter, if that fails, go to depth hold
210
if (!mode_auto.auto_loiter_start()) {
211
set_mode(Mode::Number::ALT_HOLD, ModeReason::MISSION_END);
212
}
213
}
214
215
/********************************************************************************/
216
// Nav (Must) commands
217
/********************************************************************************/
218
219
// do_nav_wp - initiate move to next waypoint
220
void Sub::do_nav_wp(const AP_Mission::Mission_Command& cmd)
221
{
222
Location target_loc(cmd.content.location);
223
// use current lat, lon if zero
224
if (target_loc.lat == 0 && target_loc.lng == 0) {
225
target_loc.lat = current_loc.lat;
226
target_loc.lng = current_loc.lng;
227
}
228
// use current altitude if not provided
229
if (target_loc.alt == 0) {
230
// set to current altitude but in command's alt frame
231
int32_t curr_alt;
232
if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
233
target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
234
} else {
235
// default to current altitude as alt-above-home
236
target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
237
}
238
}
239
240
// this will be used to remember the time in millis after we reach or pass the WP.
241
loiter_time = 0;
242
// this is the delay, stored in seconds
243
loiter_time_max = cmd.p1;
244
245
// Set wp navigation target
246
mode_auto.auto_wp_start(target_loc);
247
}
248
249
// do_surface - initiate surface procedure
250
void Sub::do_surface(const AP_Mission::Mission_Command& cmd)
251
{
252
Location target_location;
253
254
// if location provided we fly to that location at current altitude
255
if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
256
// set state to go to location
257
auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
258
259
// calculate and set desired location below surface target
260
// convert to location class
261
target_location = Location(cmd.content.location);
262
263
// decide if we will use terrain following
264
int32_t curr_terr_alt_cm, target_terr_alt_cm;
265
if (current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt_cm) &&
266
target_location.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, target_terr_alt_cm)) {
267
// if using terrain, set target altitude to current altitude above terrain
268
target_location.set_alt_cm(curr_terr_alt_cm, Location::AltFrame::ABOVE_TERRAIN);
269
} else {
270
// set target altitude to current altitude above home
271
target_location.set_alt_cm(current_loc.alt, Location::AltFrame::ABOVE_HOME);
272
}
273
} else {
274
// set surface state to ascend
275
auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
276
277
// Set waypoint destination to current location at zero depth
278
target_location = Location(current_loc.lat, current_loc.lng, 0, Location::AltFrame::ABOVE_HOME);
279
}
280
281
// Go to wp location
282
mode_auto.auto_wp_start(target_location);
283
}
284
285
void Sub::do_RTL()
286
{
287
mode_auto.auto_wp_start(ahrs.get_home());
288
}
289
290
// do_loiter_unlimited - start loitering with no end conditions
291
// note: caller should set yaw_mode
292
void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
293
{
294
// convert back to location
295
Location target_loc(cmd.content.location);
296
297
// use current location if not provided
298
if (target_loc.lat == 0 && target_loc.lng == 0) {
299
// To-Do: make this simpler
300
Vector3f temp_pos;
301
wp_nav.get_wp_stopping_point_xy(temp_pos.xy());
302
const Location temp_loc(temp_pos, Location::AltFrame::ABOVE_ORIGIN);
303
target_loc.lat = temp_loc.lat;
304
target_loc.lng = temp_loc.lng;
305
}
306
307
// In mavproxy misseditor: Abs = 0 = ALT_FRAME_ABSOLUTE
308
// Rel = 1 = ALT_FRAME_ABOVE_HOME
309
// AGL = 3 = ALT_FRAME_ABOVE_TERRAIN
310
// 2 = ALT_FRAME_ABOVE_ORIGIN, not an option in mavproxy misseditor
311
312
// use current altitude if not provided
313
// To-Do: use z-axis stopping point instead of current alt
314
if (target_loc.alt == 0) {
315
// set to current altitude but in command's alt frame
316
int32_t curr_alt;
317
if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
318
target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
319
} else {
320
// default to current altitude as alt-above-home
321
target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
322
}
323
}
324
325
// start way point navigator and provide it the desired location
326
mode_auto.auto_wp_start(target_loc);
327
}
328
329
// do_circle - initiate moving in a circle
330
void Sub::do_circle(const AP_Mission::Mission_Command& cmd)
331
{
332
Location circle_center(cmd.content.location);
333
334
// default lat/lon to current position if not provided
335
// To-Do: use stopping point or position_controller's target instead of current location to avoid jerk?
336
if (circle_center.lat == 0 && circle_center.lng == 0) {
337
circle_center.lat = current_loc.lat;
338
circle_center.lng = current_loc.lng;
339
}
340
341
// default target altitude to current altitude if not provided
342
if (circle_center.alt == 0) {
343
int32_t curr_alt;
344
if (current_loc.get_alt_cm(circle_center.get_alt_frame(),curr_alt)) {
345
// circle altitude uses frame from command
346
circle_center.set_alt_cm(curr_alt,circle_center.get_alt_frame());
347
} else {
348
// default to current altitude above origin
349
circle_center.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
350
LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
351
}
352
}
353
354
// calculate radius
355
uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
356
if (cmd.type_specific_bits & (1U << 0)) {
357
circle_radius_m *= 10;
358
}
359
360
361
// true if circle should be ccw
362
const bool circle_direction_ccw = cmd.content.location.loiter_ccw;
363
364
// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
365
mode_auto.auto_circle_movetoedge_start(circle_center, circle_radius_m, circle_direction_ccw);
366
}
367
368
// do_loiter_time - initiate loitering at a point for a given time period
369
// note: caller should set yaw_mode
370
void Sub::do_loiter_time(const AP_Mission::Mission_Command& cmd)
371
{
372
// re-use loiter unlimited
373
do_loiter_unlimited(cmd);
374
375
// setup loiter timer
376
loiter_time = 0;
377
loiter_time_max = cmd.p1; // units are (seconds)
378
}
379
380
#if NAV_GUIDED
381
// do_nav_guided_enable - initiate accepting commands from external nav computer
382
void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
383
{
384
if (cmd.p1 > 0) {
385
// initialise guided limits
386
mode_auto.guided_limit_init_time_and_pos();
387
388
// set navigation target
389
mode_auto.auto_nav_guided_start();
390
}
391
}
392
#endif // NAV_GUIDED
393
394
// do_nav_delay - Delay the next navigation command
395
void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)
396
{
397
nav_delay_time_start_ms = AP_HAL::millis();
398
399
if (cmd.content.nav_delay.seconds > 0) {
400
// relative delay
401
nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
402
} else {
403
// absolute delay to utc time
404
#if AP_RTC_ENABLED
405
nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
406
#else
407
nav_delay_time_max_ms = 0;
408
#endif
409
}
410
gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));
411
}
412
413
#if NAV_GUIDED
414
// do_guided_limits - pass guided limits to guided controller
415
void Sub::do_guided_limits(const AP_Mission::Mission_Command& cmd)
416
{
417
mode_guided.guided_limit_set(cmd.p1 * 1000, // convert seconds to ms
418
cmd.content.guided_limits.alt_min * 100.0f, // convert meters to cm
419
cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm
420
cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm
421
}
422
#endif
423
424
/********************************************************************************/
425
// Verify Nav (Must) commands
426
/********************************************************************************/
427
428
// verify_nav_wp - check if we have reached the next way point
429
bool Sub::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
430
{
431
// check if we have reached the waypoint
432
if (!wp_nav.reached_wp_destination()) {
433
return false;
434
}
435
436
// play a tone
437
AP_Notify::events.waypoint_complete = 1;
438
439
// start timer if necessary
440
if (loiter_time == 0) {
441
loiter_time = AP_HAL::millis();
442
}
443
444
// check if timer has run out
445
if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) {
446
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
447
return true;
448
}
449
450
return false;
451
}
452
453
// verify_surface - returns true if surface procedure has been completed
454
bool Sub::verify_surface(const AP_Mission::Mission_Command& cmd)
455
{
456
bool retval = false;
457
458
switch (auto_surface_state) {
459
case AUTO_SURFACE_STATE_GO_TO_LOCATION:
460
// check if we've reached the location
461
if (wp_nav.reached_wp_destination()) {
462
// Set target to current xy and zero depth
463
// TODO get xy target from current wp destination, because current location may be acceptance-radius away from original destination
464
Location target_location(cmd.content.location.lat, cmd.content.location.lng, 0, Location::AltFrame::ABOVE_HOME);
465
466
mode_auto.auto_wp_start(target_location);
467
468
// advance to next state
469
auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
470
}
471
break;
472
473
case AUTO_SURFACE_STATE_ASCEND:
474
if (wp_nav.reached_wp_destination()) {
475
retval = true;
476
}
477
break;
478
479
default:
480
// this should never happen
481
// TO-DO: log an error
482
retval = true;
483
break;
484
}
485
486
// true is returned if we've successfully surfaced
487
return retval;
488
}
489
490
bool Sub::verify_RTL() {
491
return wp_nav.reached_wp_destination();
492
}
493
494
bool Sub::verify_loiter_unlimited()
495
{
496
return false;
497
}
498
499
// verify_loiter_time - check if we have loitered long enough
500
bool Sub::verify_loiter_time()
501
{
502
// return immediately if we haven't reached our destination
503
if (!wp_nav.reached_wp_destination()) {
504
return false;
505
}
506
507
// start our loiter timer
508
if (loiter_time == 0) {
509
loiter_time = AP_HAL::millis();
510
}
511
512
// check if loiter timer has run out
513
return (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max);
514
}
515
516
// verify_circle - check if we have circled the point enough
517
bool Sub::verify_circle(const AP_Mission::Mission_Command& cmd)
518
{
519
// check if we've reached the edge
520
if (auto_mode == Auto_CircleMoveToEdge) {
521
if (wp_nav.reached_wp_destination()) {
522
Vector3f circle_center;
523
UNUSED_RESULT(cmd.content.location.get_vector_from_origin_NEU(circle_center));
524
525
// set target altitude if not provided
526
if (is_zero(circle_center.z)) {
527
circle_center.z = inertial_nav.get_position_z_up_cm();
528
}
529
530
// set lat/lon position if not provided
531
if (cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
532
circle_center.xy() = inertial_nav.get_position_xy_cm();
533
}
534
535
// start circling
536
mode_auto.auto_circle_start();
537
}
538
return false;
539
}
540
const float turns = cmd.get_loiter_turns();
541
542
// check if we have completed circling
543
return fabsf(sub.circle_nav.get_angle_total()/M_2PI) >= turns;
544
}
545
546
#if NAV_GUIDED
547
// verify_nav_guided - check if we have breached any limits
548
bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
549
{
550
// if disabling guided mode then immediately return true so we move to next command
551
if (cmd.p1 == 0) {
552
return true;
553
}
554
555
// check time and position limits
556
return mode_auto.guided_limit_check();
557
}
558
#endif // NAV_GUIDED
559
560
// verify_nav_delay - check if we have waited long enough
561
bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
562
{
563
if (AP_HAL::millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {
564
nav_delay_time_max_ms = 0;
565
return true;
566
}
567
return false;
568
}
569
570
/********************************************************************************/
571
// Condition (May) commands
572
/********************************************************************************/
573
574
void Sub::do_wait_delay(const AP_Mission::Mission_Command& cmd)
575
{
576
condition_start = AP_HAL::millis();
577
condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
578
}
579
580
void Sub::do_within_distance(const AP_Mission::Mission_Command& cmd)
581
{
582
condition_value = cmd.content.distance.meters * 100;
583
}
584
585
void Sub::do_yaw(const AP_Mission::Mission_Command& cmd)
586
{
587
sub.mode_auto.set_auto_yaw_look_at_heading(
588
cmd.content.yaw.angle_deg,
589
cmd.content.yaw.turn_rate_dps,
590
cmd.content.yaw.direction,
591
cmd.content.yaw.relative_angle);
592
}
593
594
595
/********************************************************************************/
596
// Verify Condition (May) commands
597
/********************************************************************************/
598
599
bool Sub::verify_wait_delay()
600
{
601
if (AP_HAL::millis() - condition_start > (uint32_t)MAX(condition_value, 0)) {
602
condition_value = 0;
603
return true;
604
}
605
return false;
606
}
607
608
bool Sub::verify_within_distance()
609
{
610
if (wp_nav.get_wp_distance_to_destination() < (uint32_t)MAX(condition_value,0)) {
611
condition_value = 0;
612
return true;
613
}
614
return false;
615
}
616
617
// verify_yaw - return true if we have reached the desired heading
618
bool Sub::verify_yaw()
619
{
620
// set yaw mode if it has been changed (the waypoint controller often retakes control of yaw as it executes a new waypoint command)
621
if (auto_yaw_mode != AUTO_YAW_LOOK_AT_HEADING) {
622
sub.mode_auto.set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
623
}
624
625
// check if we are within 2 degrees of the target heading
626
return (abs(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);
627
}
628
629
/********************************************************************************/
630
// Do (Now) commands
631
/********************************************************************************/
632
633
// do_guided - start guided mode
634
bool Sub::do_guided(const AP_Mission::Mission_Command& cmd)
635
{
636
// only process guided waypoint if we are in guided mode
637
if (control_mode != Mode::Number::GUIDED && !(control_mode == Mode::Number::AUTO && auto_mode == Auto_NavGuided)) {
638
return false;
639
}
640
641
// switch to handle different commands
642
switch (cmd.id) {
643
644
case MAV_CMD_NAV_WAYPOINT: {
645
// set wp_nav's destination
646
return sub.mode_guided.guided_set_destination(cmd.content.location);
647
}
648
649
case MAV_CMD_CONDITION_YAW:
650
do_yaw(cmd);
651
return true;
652
653
default:
654
// reject unrecognised command
655
return false;
656
}
657
658
return true;
659
}
660
661
void Sub::do_change_speed(const AP_Mission::Mission_Command& cmd)
662
{
663
if (cmd.content.speed.target_ms > 0) {
664
wp_nav.set_speed_xy(cmd.content.speed.target_ms * 100.0f);
665
}
666
}
667
668
void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)
669
{
670
if (cmd.p1 == 1 || (cmd.content.location.lat == 0 && cmd.content.location.lng == 0 && cmd.content.location.alt == 0)) {
671
if (!set_home_to_current_location(false)) {
672
// silently ignore this failure
673
}
674
} else {
675
if (!set_home(cmd.content.location, false)) {
676
// silently ignore this failure
677
}
678
}
679
}
680
681
// do_roi - starts actions required by MAV_CMD_NAV_ROI
682
// this involves either moving the camera to point at the ROI (region of interest)
683
// and possibly rotating the vehicle to point at the ROI if our mount type does not support a yaw feature
684
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
685
void Sub::do_roi(const AP_Mission::Mission_Command& cmd)
686
{
687
sub.mode_auto.set_auto_yaw_roi(cmd.content.location);
688
}
689
690
// point the camera to a specified angle
691
void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)
692
{
693
#if HAL_MOUNT_ENABLED
694
camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);
695
#endif
696
}
697
698