Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/commands_logic.cpp
9560 views
1
#include "Plane.h"
2
3
/********************************************************************************/
4
// Command Event Handlers
5
/********************************************************************************/
6
bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
7
{
8
// default to non-VTOL loiter
9
auto_state.vtol_loiter = false;
10
11
#if AP_TERRAIN_AVAILABLE
12
plane.target_altitude.terrain_following_pending = false;
13
#endif
14
15
// special handling for nav vs non-nav commands
16
if (AP_Mission::is_nav_cmd(cmd)) {
17
// set takeoff_complete to true so we don't add extra elevator
18
// except in a takeoff
19
auto_state.takeoff_complete = true;
20
21
nav_controller->set_data_is_stale();
22
23
// start non-idle
24
auto_state.idle_mode = false;
25
26
// reset loiter start time. New command is a new loiter
27
loiter.start_time_ms = 0;
28
29
// Mission lookahead is only valid in auto
30
if (control_mode == &mode_auto) {
31
AP_Mission::Mission_Command next_nav_cmd;
32
const uint16_t next_index = mission.get_current_nav_index() + 1;
33
const bool have_next_cmd = mission.get_next_nav_cmd(next_index, next_nav_cmd);
34
auto_state.wp_is_land_approach = have_next_cmd && (next_nav_cmd.id == MAV_CMD_NAV_LAND);
35
#if HAL_QUADPLANE_ENABLED
36
if (have_next_cmd && quadplane.is_vtol_land(next_nav_cmd.id)) {
37
auto_state.wp_is_land_approach = false;
38
}
39
#endif
40
}
41
}
42
43
switch(cmd.id) {
44
45
case MAV_CMD_NAV_TAKEOFF:
46
crash_state.is_crashed = false;
47
#if HAL_QUADPLANE_ENABLED
48
if (quadplane.is_vtol_takeoff(cmd.id)) {
49
return quadplane.do_vtol_takeoff(cmd);
50
}
51
#endif
52
do_takeoff(cmd);
53
break;
54
55
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
56
do_nav_wp(cmd);
57
break;
58
59
case MAV_CMD_NAV_LAND: // LAND to Waypoint
60
#if HAL_QUADPLANE_ENABLED
61
if (quadplane.is_vtol_land(cmd.id)) {
62
crash_state.is_crashed = false;
63
return quadplane.do_vtol_land(cmd);
64
}
65
#endif
66
do_land(cmd);
67
break;
68
69
case MAV_CMD_NAV_LOITER_UNLIM: // Loiter indefinitely
70
do_loiter_unlimited(cmd);
71
break;
72
73
case MAV_CMD_NAV_LOITER_TURNS: // Loiter N Times
74
do_loiter_turns(cmd);
75
break;
76
77
case MAV_CMD_NAV_LOITER_TIME:
78
do_loiter_time(cmd);
79
break;
80
81
case MAV_CMD_NAV_LOITER_TO_ALT:
82
do_loiter_to_alt(cmd);
83
break;
84
85
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
86
set_mode(mode_rtl, ModeReason::MISSION_CMD);
87
break;
88
89
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
90
do_continue_and_change_alt(cmd);
91
break;
92
93
case MAV_CMD_NAV_ALTITUDE_WAIT:
94
do_altitude_wait(cmd);
95
break;
96
97
#if HAL_QUADPLANE_ENABLED
98
case MAV_CMD_NAV_VTOL_TAKEOFF:
99
crash_state.is_crashed = false;
100
return quadplane.do_vtol_takeoff(cmd);
101
102
case MAV_CMD_NAV_VTOL_LAND:
103
case MAV_CMD_NAV_PAYLOAD_PLACE:
104
if (quadplane.landing_with_fixed_wing_spiral_approach()) {
105
// the user wants to approach the landing in a fixed wing flight mode
106
// the waypoint will be used as a loiter_to_alt
107
// after which point the plane will compute the optimal into the wind direction
108
// and fly in on that direction towards the landing waypoint
109
// it will then transition to VTOL and do a normal quadplane landing
110
do_landing_vtol_approach(cmd);
111
break;
112
} else {
113
return quadplane.do_vtol_land(cmd);
114
}
115
#endif
116
117
// Conditional commands
118
119
case MAV_CMD_CONDITION_DELAY:
120
do_wait_delay(cmd);
121
break;
122
123
case MAV_CMD_CONDITION_DISTANCE:
124
do_within_distance(cmd);
125
break;
126
127
// Do commands
128
129
case MAV_CMD_DO_CHANGE_SPEED:
130
do_change_speed(cmd);
131
break;
132
133
case MAV_CMD_DO_SET_HOME:
134
do_set_home(cmd);
135
break;
136
137
case MAV_CMD_DO_INVERTED_FLIGHT:
138
if (cmd.p1 == 0 || cmd.p1 == 1) {
139
auto_state.inverted_flight = (bool)cmd.p1;
140
gcs().send_text(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1);
141
}
142
break;
143
144
case MAV_CMD_DO_RETURN_PATH_START:
145
case MAV_CMD_DO_LAND_START:
146
break;
147
148
case MAV_CMD_DO_AUTOTUNE_ENABLE:
149
autotune_enable(cmd.p1);
150
break;
151
152
#if HAL_MOUNT_ENABLED
153
// Sets the region of interest (ROI) for a sensor set or the
154
// vehicle itself. This can then be used by the vehicles control
155
// system to control the vehicle attitude and the attitude of various
156
// devices such as cameras.
157
// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
158
// ROI_NONE can be handled by the regular ROI handler because lat, lon, alt are always zero
159
case MAV_CMD_DO_SET_ROI_LOCATION:
160
case MAV_CMD_DO_SET_ROI_NONE:
161
case MAV_CMD_DO_SET_ROI:
162
if (!cmd.content.location.initialised()) {
163
// switch off the camera tracking if enabled
164
if (camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
165
camera_mount.set_mode_to_default();
166
}
167
} else {
168
// set mount's target location
169
camera_mount.set_roi_target(cmd.content.location);
170
}
171
break;
172
173
case MAV_CMD_DO_MOUNT_CONTROL: // 205
174
// point the camera to a specified angle
175
camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);
176
break;
177
#endif
178
179
#if HAL_QUADPLANE_ENABLED
180
case MAV_CMD_DO_VTOL_TRANSITION:
181
plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)cmd.content.do_vtol_transition.target_state);
182
break;
183
#endif
184
185
#if AP_ICENGINE_ENABLED
186
case MAV_CMD_DO_ENGINE_CONTROL:
187
plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control,
188
cmd.content.do_engine_control.cold_start,
189
cmd.content.do_engine_control.height_delay_cm*0.01f,
190
cmd.content.do_engine_control.allow_disarmed_start);
191
break;
192
#endif
193
194
#if AP_SCRIPTING_ENABLED
195
case MAV_CMD_NAV_SCRIPT_TIME:
196
do_nav_script_time(cmd);
197
break;
198
#endif
199
200
case MAV_CMD_NAV_DELAY:
201
mode_auto.do_nav_delay(cmd);
202
break;
203
204
default:
205
// unable to use the command, allow the vehicle to try the next command
206
return false;
207
}
208
209
return true;
210
}
211
212
/*******************************************************************************
213
Verify command Handlers
214
215
Each type of mission element has a "verify" operation. The verify
216
operation returns true when the mission element has completed and we
217
should move onto the next mission element.
218
Return true if we do not recognize the command so that we move on to the next command
219
*******************************************************************************/
220
221
bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Returns true if command complete
222
{
223
switch(cmd.id) {
224
225
case MAV_CMD_NAV_TAKEOFF:
226
#if HAL_QUADPLANE_ENABLED
227
if (quadplane.is_vtol_takeoff(cmd.id)) {
228
return quadplane.verify_vtol_takeoff(cmd);
229
}
230
#endif
231
return verify_takeoff();
232
233
case MAV_CMD_NAV_WAYPOINT:
234
return verify_nav_wp(cmd);
235
236
case MAV_CMD_NAV_LAND:
237
#if HAL_QUADPLANE_ENABLED
238
if (quadplane.is_vtol_land(cmd.id)) {
239
return quadplane.verify_vtol_land();
240
}
241
#endif
242
if (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
243
return landing.verify_abort_landing(prev_WP_loc, next_WP_loc, current_loc, auto_state.takeoff_altitude_rel_cm, throttle_suppressed);
244
245
} else {
246
// use rangefinder to correct if possible
247
bool rangefinder_active = false;
248
float height = plane.get_landing_height(rangefinder_active);
249
250
// for flare calculations we don't want to use the terrain
251
// correction as otherwise we will flare early on rising
252
// ground
253
height -= auto_state.terrain_correction;
254
return landing.verify_land(prev_WP_loc, next_WP_loc, current_loc,
255
height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(),
256
rangefinder_active);
257
}
258
259
case MAV_CMD_NAV_LOITER_UNLIM:
260
return verify_loiter_unlim(cmd);
261
262
case MAV_CMD_NAV_LOITER_TURNS:
263
return verify_loiter_turns(cmd);
264
265
case MAV_CMD_NAV_LOITER_TIME:
266
return verify_loiter_time();
267
268
case MAV_CMD_NAV_LOITER_TO_ALT:
269
return verify_loiter_to_alt(cmd);
270
271
272
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
273
return verify_continue_and_change_alt();
274
275
case MAV_CMD_NAV_ALTITUDE_WAIT:
276
return mode_auto.verify_altitude_wait(cmd);
277
278
#if HAL_QUADPLANE_ENABLED
279
case MAV_CMD_NAV_VTOL_TAKEOFF:
280
return quadplane.verify_vtol_takeoff(cmd);
281
case MAV_CMD_NAV_VTOL_LAND:
282
case MAV_CMD_NAV_PAYLOAD_PLACE:
283
if (quadplane.landing_with_fixed_wing_spiral_approach() && !verify_landing_vtol_approach(cmd)) {
284
// verify_landing_vtol_approach will return true once we have completed the approach,
285
// in which case we fall over to normal vtol landing code
286
return false;
287
} else {
288
return quadplane.verify_vtol_land();
289
}
290
#endif // HAL_QUADPLANE_ENABLED
291
292
// Conditional commands
293
294
case MAV_CMD_CONDITION_DELAY:
295
return verify_wait_delay();
296
297
case MAV_CMD_CONDITION_DISTANCE:
298
return verify_within_distance();
299
300
#if AP_SCRIPTING_ENABLED
301
case MAV_CMD_NAV_SCRIPT_TIME:
302
return verify_nav_script_time(cmd);
303
#endif
304
305
case MAV_CMD_NAV_DELAY:
306
return mode_auto.verify_nav_delay(cmd);
307
308
// do commands (always return true)
309
case MAV_CMD_DO_CHANGE_SPEED:
310
case MAV_CMD_DO_SET_HOME:
311
case MAV_CMD_DO_INVERTED_FLIGHT:
312
case MAV_CMD_DO_RETURN_PATH_START:
313
case MAV_CMD_DO_LAND_START:
314
case MAV_CMD_DO_FENCE_ENABLE:
315
case MAV_CMD_DO_AUTOTUNE_ENABLE:
316
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
317
case MAV_CMD_DO_SET_ROI_LOCATION:
318
case MAV_CMD_DO_SET_ROI_NONE:
319
case MAV_CMD_DO_SET_ROI:
320
case MAV_CMD_DO_MOUNT_CONTROL:
321
case MAV_CMD_DO_VTOL_TRANSITION:
322
case MAV_CMD_DO_ENGINE_CONTROL:
323
return true;
324
325
default:
326
// error message
327
gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
328
// return true if we do not recognize the command so that we move on to the next command
329
return true;
330
}
331
}
332
333
/********************************************************************************/
334
// Nav (Must) commands
335
/********************************************************************************/
336
337
void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
338
{
339
auto_state.next_wp_crosstrack = false;
340
auto_state.crosstrack = false;
341
prev_WP_loc = current_loc;
342
next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);
343
344
fix_terrain_WP(next_WP_loc, __LINE__);
345
346
setup_terrain_target_alt(next_WP_loc);
347
set_target_altitude_location(next_WP_loc);
348
349
if (aparm.loiter_radius < 0) {
350
loiter.direction = -1;
351
} else {
352
loiter.direction = 1;
353
}
354
355
setup_alt_slope();
356
setup_turn_angle();
357
}
358
359
Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const
360
{
361
#if HAL_RALLY_ENABLED
362
return plane.rally.calc_best_rally_or_home_location(_current_loc, rtl_home_alt_amsl_cm);
363
#else
364
return Location {
365
plane.home.lat,
366
plane.home.lng,
367
int32_t(rtl_home_alt_amsl_cm),
368
Location::AltFrame::ABSOLUTE
369
};
370
#endif
371
}
372
373
/*
374
start a NAV_TAKEOFF command
375
*/
376
void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)
377
{
378
prev_WP_loc = current_loc;
379
set_next_WP(cmd.content.location);
380
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
381
auto_state.takeoff_pitch_cd = (int16_t)cmd.p1 * 100;
382
if (auto_state.takeoff_pitch_cd <= 0) {
383
// if the mission doesn't specify a pitch use 4 degrees
384
auto_state.takeoff_pitch_cd = 400;
385
}
386
auto_state.takeoff_altitude_rel_cm = next_WP_loc.alt - home.alt;
387
next_WP_loc.lat = home.lat + 10;
388
next_WP_loc.lng = home.lng + 10;
389
auto_state.takeoff_complete = false; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction.
390
auto_state.rotation_complete = false;
391
auto_state.height_below_takeoff_to_level_off_cm = 0;
392
// Flag also used to override "on the ground" throttle disable
393
394
// zero locked course
395
steer_state.locked_course_err = 0;
396
steer_state.hold_course_cd = -1;
397
auto_state.baro_takeoff_alt = barometer.get_altitude();
398
}
399
400
void Plane::do_nav_wp(const AP_Mission::Mission_Command& cmd)
401
{
402
set_next_WP(cmd.content.location);
403
}
404
405
void Plane::do_land(const AP_Mission::Mission_Command& cmd)
406
{
407
set_next_WP(cmd.content.location);
408
409
// configure abort altitude and pitch
410
// if NAV_LAND has an abort altitude then use it, else use last takeoff, else use 30m
411
if (cmd.p1 > 0) {
412
auto_state.takeoff_altitude_rel_cm = (int16_t)cmd.p1 * 100;
413
} else if (auto_state.takeoff_altitude_rel_cm <= 0) {
414
auto_state.takeoff_altitude_rel_cm = 3000;
415
}
416
417
if (auto_state.takeoff_pitch_cd <= 0) {
418
// If no takeoff command has ever been used, default to a conservative 10deg
419
auto_state.takeoff_pitch_cd = 1000;
420
}
421
422
#if AP_RANGEFINDER_ENABLED
423
// zero rangefinder state, start to accumulate good samples now
424
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
425
#endif
426
427
landing.do_land(cmd, relative_altitude);
428
429
if (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
430
// if we were in an abort we need to explicitly move out of the abort state, as it's sticky
431
set_flight_stage(AP_FixedWing::FlightStage::LAND);
432
}
433
}
434
435
#if HAL_QUADPLANE_ENABLED
436
void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd)
437
{
438
//set target alt
439
Location loc = cmd.content.location;
440
loc.sanitize(current_loc);
441
set_next_WP(loc);
442
443
vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT;
444
}
445
#endif
446
447
void Plane::loiter_set_direction_wp(const AP_Mission::Mission_Command& cmd)
448
{
449
if (cmd.content.location.loiter_ccw) {
450
loiter.direction = -1;
451
} else {
452
loiter.direction = 1;
453
}
454
}
455
456
void Plane::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
457
{
458
Location cmdloc = cmd.content.location;
459
cmdloc.sanitize(current_loc);
460
set_next_WP(cmdloc);
461
loiter_set_direction_wp(cmd);
462
}
463
464
void Plane::do_loiter_turns(const AP_Mission::Mission_Command& cmd)
465
{
466
Location cmdloc = cmd.content.location;
467
cmdloc.sanitize(current_loc);
468
set_next_WP(cmdloc);
469
loiter_set_direction_wp(cmd);
470
const float turns = cmd.get_loiter_turns();
471
472
loiter.total_cd = (uint32_t)(turns * 36000UL);
473
condition_value = 1; // used to signify primary turns goal not yet met
474
}
475
476
void Plane::do_loiter_time(const AP_Mission::Mission_Command& cmd)
477
{
478
Location cmdloc = cmd.content.location;
479
cmdloc.sanitize(current_loc);
480
set_next_WP(cmdloc);
481
loiter_set_direction_wp(cmd);
482
483
// we set start_time_ms when we reach the waypoint
484
loiter.time_max_ms = cmd.p1 * (uint32_t)1000; // convert sec to ms
485
condition_value = 1; // used to signify primary time goal not yet met
486
}
487
488
void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd)
489
{
490
// select heading method. Either mission, gps bearing projection or yaw based
491
// If prev_WP_loc and next_WP_loc are different then an accurate wp based bearing can
492
// be computed. However, if we had just changed modes before this, such as an aborted landing
493
// via mode change, the prev and next wps are the same.
494
float bearing;
495
if (!prev_WP_loc.same_latlon_as(next_WP_loc)) {
496
// use waypoint based bearing, this is the usual case
497
steer_state.hold_course_cd = -1;
498
} else if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
499
// use gps ground course based bearing hold
500
steer_state.hold_course_cd = -1;
501
bearing = AP::gps().ground_course();
502
next_WP_loc.offset_bearing(bearing, 1000); // push it out 1km
503
} else {
504
// use yaw based bearing hold
505
steer_state.hold_course_cd = wrap_360_cd(ahrs.yaw_sensor);
506
bearing = ahrs.get_yaw_deg();
507
next_WP_loc.offset_bearing(bearing, 1000); // push it out 1km
508
}
509
510
if (cmd.content.location.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {
511
next_WP_loc.copy_alt_from(cmd.content.location);
512
} else {
513
int32_t alt_abs_cm;
514
// if this fails we don't change alt
515
if (cmd.content.location.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_abs_cm)) {
516
next_WP_loc.set_alt_cm(alt_abs_cm,
517
Location::AltFrame::ABSOLUTE);
518
}
519
}
520
condition_value = cmd.p1;
521
reset_offset_altitude();
522
}
523
524
void Plane::do_altitude_wait(const AP_Mission::Mission_Command& cmd)
525
{
526
// set all servos to trim until we reach altitude or descent speed
527
auto_state.idle_mode = true;
528
#if AP_PLANE_GLIDER_PULLUP_ENABLED
529
mode_auto.pullup.reset();
530
#endif
531
}
532
533
void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
534
{
535
//set target alt
536
Location loc = cmd.content.location;
537
loc.sanitize(current_loc);
538
set_next_WP(loc);
539
loiter_set_direction_wp(cmd);
540
541
// init to 0, set to 1 when altitude is reached
542
condition_value = 0;
543
}
544
545
// do_nav_delay - Delay the next navigation command
546
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
547
{
548
nav_delay.time_start_ms = millis();
549
550
if (cmd.content.nav_delay.seconds > 0) {
551
// relative delay
552
nav_delay.time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
553
} else {
554
// absolute delay to utc time
555
#if AP_RTC_ENABLED
556
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);
557
#else
558
nav_delay.time_max_ms = 0;
559
#endif
560
}
561
gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay.time_max_ms/1000));
562
}
563
564
/********************************************************************************/
565
// Verify Nav (Must) commands
566
/********************************************************************************/
567
bool Plane::verify_takeoff()
568
{
569
bool trust_ahrs_yaw = AP::ahrs().initialised();
570
#if AP_AHRS_DCM_ENABLED
571
trust_ahrs_yaw |= ahrs.dcm_yaw_initialised();
572
#endif
573
if (trust_ahrs_yaw && steer_state.hold_course_cd == -1) {
574
// once we reach sufficient speed for good GPS course
575
// estimation we save our current GPS ground course
576
// corrected for summed yaw to set the take off
577
// course. This keeps wings level until we are ready to
578
// rotate, and also allows us to cope with arbitrary
579
// compass errors for auto takeoff
580
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
581
gps.ground_speed() > GPS_GND_CRS_MIN_SPD &&
582
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
583
float takeoff_course = wrap_PI(radians(gps.ground_course())) - steer_state.locked_course_err;
584
takeoff_course = wrap_PI(takeoff_course);
585
steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);
586
gcs().send_text(MAV_SEVERITY_INFO, "Holding course %d at %.1fm/s (%.1f)",
587
(int)steer_state.hold_course_cd,
588
(double)gps.ground_speed(),
589
(double)degrees(steer_state.locked_course_err));
590
}
591
}
592
593
if (steer_state.hold_course_cd != -1) {
594
// call navigation controller for heading hold
595
nav_controller->update_heading_hold(steer_state.hold_course_cd);
596
} else {
597
nav_controller->update_level_flight();
598
}
599
600
// check for optional takeoff timeout
601
if (plane.check_takeoff_timeout()) {
602
mission.reset();
603
}
604
605
// see if we have reached takeoff altitude
606
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
607
if (
608
relative_alt_cm > auto_state.takeoff_altitude_rel_cm || // altitude reached
609
plane.check_takeoff_timeout_level_off() // pitch level-off maneuver has timed out
610
) {
611
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",
612
(double)(relative_alt_cm*0.01f));
613
steer_state.hold_course_cd = -1;
614
auto_state.takeoff_complete = true;
615
next_WP_loc = prev_WP_loc = current_loc;
616
617
#if AP_FENCE_ENABLED
618
plane.fence.auto_enable_fence_after_takeoff();
619
#endif
620
621
// don't cross-track on completion of takeoff, as otherwise we
622
// can end up doing too sharp a turn
623
auto_state.next_wp_crosstrack = false;
624
return true;
625
} else {
626
return false;
627
}
628
}
629
630
/*
631
update navigation for normal mission waypoints. Return true when the
632
waypoint is complete
633
*/
634
bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
635
{
636
steer_state.hold_course_cd = -1;
637
638
// depending on the pass by flag either go to waypoint in regular manner or
639
// fly past it for set distance along the line of waypoints
640
Location flex_next_WP_loc = next_WP_loc;
641
642
uint8_t cmd_passby = HIGHBYTE(cmd.p1); // distance in meters to pass beyond the wp
643
uint8_t cmd_acceptance_distance = LOWBYTE(cmd.p1); // radius in meters to accept reaching the wp
644
645
if (cmd_passby > 0) {
646
const float dist = prev_WP_loc.get_distance(flex_next_WP_loc);
647
const float bearing_deg = degrees(prev_WP_loc.get_bearing(flex_next_WP_loc));
648
649
if (is_positive(dist)) {
650
flex_next_WP_loc.offset_bearing(bearing_deg, cmd_passby);
651
}
652
}
653
654
if (auto_state.crosstrack) {
655
nav_controller->update_waypoint(prev_WP_loc, flex_next_WP_loc);
656
} else {
657
nav_controller->update_waypoint(current_loc, flex_next_WP_loc);
658
}
659
660
// see if the user has specified a maximum distance to waypoint
661
// If override with p3 - then this is not used as it will overfly badly
662
if (g.waypoint_max_radius > 0 &&
663
auto_state.wp_distance > (uint16_t)g.waypoint_max_radius) {
664
if (current_loc.past_interval_finish_line(prev_WP_loc, flex_next_WP_loc)) {
665
// this is needed to ensure completion of the waypoint
666
if (cmd_passby == 0) {
667
prev_WP_loc = current_loc;
668
}
669
}
670
return false;
671
}
672
673
float acceptance_distance_m = 0; // default to: if overflown - let it fly up to the point
674
if (cmd_acceptance_distance > 0) {
675
// allow user to override acceptance radius
676
acceptance_distance_m = cmd_acceptance_distance;
677
} else if (cmd_passby == 0) {
678
acceptance_distance_m = nav_controller->turn_distance(get_wp_radius(), auto_state.next_turn_angle);
679
}
680
const float wp_dist = current_loc.get_distance(flex_next_WP_loc);
681
if (wp_dist <= acceptance_distance_m) {
682
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%i dist %um",
683
(unsigned)mission.get_current_nav_cmd().index,
684
(unsigned)current_loc.get_distance(flex_next_WP_loc));
685
return true;
686
}
687
688
// have we flown past the waypoint?
689
if (current_loc.past_interval_finish_line(prev_WP_loc, flex_next_WP_loc)) {
690
gcs().send_text(MAV_SEVERITY_INFO, "Passed waypoint #%i dist %um",
691
(unsigned)mission.get_current_nav_cmd().index,
692
(unsigned)current_loc.get_distance(flex_next_WP_loc));
693
return true;
694
}
695
696
return false;
697
}
698
699
bool Plane::verify_loiter_unlim(const AP_Mission::Mission_Command &cmd)
700
{
701
// else use mission radius
702
update_loiter(cmd.p1);
703
return false;
704
}
705
706
bool Plane::verify_loiter_time()
707
{
708
bool result = false;
709
// mission radius is always aparm.loiter_radius
710
update_loiter(0);
711
712
if (loiter.start_time_ms == 0) {
713
if (reached_loiter_target() && loiter.sum_cd > 1) {
714
// we've reached the target, start the timer
715
loiter.start_time_ms = millis();
716
}
717
} else if (condition_value != 0) {
718
// primary goal, loiter time
719
if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) {
720
// primary goal completed, initialize secondary heading goal
721
condition_value = 0;
722
result = verify_loiter_heading(true);
723
}
724
} else {
725
// secondary goal, loiter to heading
726
result = verify_loiter_heading(false);
727
}
728
729
if (result) {
730
gcs().send_text(MAV_SEVERITY_INFO,"Loiter time complete");
731
auto_state.vtol_loiter = false;
732
}
733
return result;
734
}
735
736
bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd)
737
{
738
bool result = false;
739
uint16_t radius = HIGHBYTE(cmd.p1);
740
if (cmd.type_specific_bits & (1U<<0)) {
741
// special storage handling allows for larger radii
742
radius *= 10;
743
}
744
update_loiter(radius);
745
746
// LOITER_TURNS makes no sense as VTOL
747
auto_state.vtol_loiter = false;
748
749
if (!reached_loiter_target()) {
750
result = false;
751
} else if (condition_value != 0) {
752
// primary goal, loiter turns
753
if (loiter.sum_cd > loiter.total_cd && loiter.sum_cd > 1) {
754
// primary goal completed, initialize secondary heading goal
755
condition_value = 0;
756
result = verify_loiter_heading(true);
757
}
758
} else {
759
// secondary goal, loiter to heading
760
result = verify_loiter_heading(false);
761
}
762
763
if (result) {
764
gcs().send_text(MAV_SEVERITY_INFO,"Loiter orbits complete");
765
}
766
return result;
767
}
768
769
/*
770
verify a LOITER_TO_ALT command. This involves checking we have
771
reached both the desired altitude and desired heading. The desired
772
altitude only needs to be reached once.
773
*/
774
bool Plane::verify_loiter_to_alt(const AP_Mission::Mission_Command &cmd)
775
{
776
bool result = false;
777
778
update_loiter(cmd.p1);
779
780
// condition_value == 0 means alt has never been reached
781
if (condition_value == 0) {
782
// primary goal, loiter to alt
783
if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_achieve_target_alt)) {
784
// primary goal completed, initialize secondary heading goal
785
if (loiter.unable_to_achieve_target_alt) {
786
gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt was stuck at %d", int(current_loc.alt/100));
787
}
788
789
condition_value = 1;
790
result = verify_loiter_heading(true);
791
}
792
} else {
793
// secondary goal, loiter to heading
794
result = verify_loiter_heading(false);
795
}
796
797
if (result) {
798
gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt complete");
799
}
800
return result;
801
}
802
803
804
bool Plane::verify_continue_and_change_alt()
805
{
806
// is waypoint info not available and heading hold is?
807
if (prev_WP_loc.same_latlon_as(next_WP_loc) &&
808
steer_state.hold_course_cd != -1) {
809
//keep flying the same course with fixed steering heading computed at start if cmd
810
nav_controller->update_heading_hold(steer_state.hold_course_cd);
811
}
812
else {
813
// Is the next_WP less than 200 m away?
814
if (current_loc.get_distance(next_WP_loc) < 200.0f) {
815
//push another 300 m down the line
816
int32_t next_wp_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);
817
next_WP_loc.offset_bearing(next_wp_bearing_cd * 0.01f, 300.0f);
818
}
819
820
//keep flying the same course
821
nav_controller->update_waypoint(prev_WP_loc, next_WP_loc);
822
}
823
824
//climbing?
825
if (condition_value == 1 && adjusted_altitude_cm() >= next_WP_loc.alt) {
826
return true;
827
}
828
//descending?
829
else if (condition_value == 2 &&
830
adjusted_altitude_cm() <= next_WP_loc.alt) {
831
return true;
832
}
833
//don't care if we're climbing or descending
834
else if (labs(adjusted_altitude_cm() - next_WP_loc.alt) <= 500) {
835
return true;
836
}
837
838
return false;
839
}
840
841
/*
842
see if we have reached altitude or descent speed
843
*/
844
bool ModeAuto::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
845
{
846
#if AP_PLANE_GLIDER_PULLUP_ENABLED
847
if (pullup.in_pullup()) {
848
return pullup.verify_pullup();
849
}
850
#endif
851
852
/*
853
the target altitude in param1 is always AMSL
854
*/
855
const float alt_diff = plane.current_loc.alt*0.01 - cmd.content.altitude_wait.altitude;
856
bool completed = false;
857
if (alt_diff > 0) {
858
gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude");
859
completed = true;
860
} else if (cmd.content.altitude_wait.descent_rate > 0 &&
861
plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
862
gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)plane.auto_state.sink_rate);
863
completed = true;
864
}
865
866
if (completed) {
867
#if AP_PLANE_GLIDER_PULLUP_ENABLED
868
if (pullup.pullup_start()) {
869
// we are doing a pullup, ALTITUDE_WAIT not complete until pullup is done
870
return false;
871
}
872
#endif
873
return true;
874
}
875
876
const float time_to_alt = alt_diff / MIN(plane.auto_state.sink_rate, -0.01);
877
878
/*
879
if requested, wiggle servos
880
881
we don't start a wiggle if we expect to release soon as we don't
882
want the servos to be off trim at the time of release
883
*/
884
if (cmd.content.altitude_wait.wiggle_time != 0 &&
885
(plane.auto_state.sink_rate > 0 || time_to_alt > cmd.content.altitude_wait.wiggle_time*5)) {
886
if (wiggle.stage == 0 &&
887
AP_HAL::millis() - wiggle.last_ms > cmd.content.altitude_wait.wiggle_time*1000) {
888
wiggle.stage = 1;
889
wiggle.last_ms = AP_HAL::millis();
890
// idle_wiggle_stage is updated in wiggle_servos()
891
}
892
}
893
894
return false;
895
}
896
897
// verify_nav_delay - check if we have waited long enough
898
bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
899
{
900
if (AP::arming().is_armed_and_safety_off()) {
901
// don't delay while armed, we need a nav controller running
902
return true;
903
}
904
if (millis() - nav_delay.time_start_ms > nav_delay.time_max_ms) {
905
nav_delay.time_max_ms = 0;
906
return true;
907
}
908
return false;
909
}
910
911
/********************************************************************************/
912
// Condition (May) commands
913
/********************************************************************************/
914
915
void Plane::do_wait_delay(const AP_Mission::Mission_Command& cmd)
916
{
917
condition_start = millis();
918
condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
919
}
920
921
void Plane::do_within_distance(const AP_Mission::Mission_Command& cmd)
922
{
923
condition_value = cmd.content.distance.meters;
924
}
925
926
/********************************************************************************/
927
// Verify Condition (May) commands
928
/********************************************************************************/
929
930
bool Plane::verify_wait_delay()
931
{
932
if ((unsigned)(millis() - condition_start) > (unsigned)condition_value) {
933
condition_value = 0;
934
return true;
935
}
936
return false;
937
}
938
939
bool Plane::verify_within_distance()
940
{
941
if (auto_state.wp_distance < MAX(condition_value,0)) {
942
condition_value = 0;
943
return true;
944
}
945
return false;
946
}
947
948
/********************************************************************************/
949
// Do (Now) commands
950
/********************************************************************************/
951
952
void Plane::do_loiter_at_location()
953
{
954
if (aparm.loiter_radius < 0) {
955
loiter.direction = -1;
956
} else {
957
loiter.direction = 1;
958
}
959
next_WP_loc = current_loc;
960
}
961
962
bool Plane::do_change_speed(const AP_Mission::Mission_Command& cmd)
963
{
964
return do_change_speed(
965
(SPEED_TYPE)cmd.content.speed.speed_type,
966
cmd.content.speed.target_ms,
967
cmd.content.speed.throttle_pct
968
);
969
}
970
971
bool Plane::do_change_speed(SPEED_TYPE speedtype, float speed_target_ms, float throttle_pct)
972
{
973
switch (speedtype) {
974
case SPEED_TYPE_AIRSPEED:
975
if (is_equal(speed_target_ms, -2.0f)) {
976
new_airspeed_cm = -1; // return to default airspeed
977
return true;
978
} else if ((speed_target_ms >= aparm.airspeed_min.get()) &&
979
(speed_target_ms <= aparm.airspeed_max.get())) {
980
new_airspeed_cm = speed_target_ms * 100; //new airspeed target for AUTO or GUIDED modes
981
gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)speed_target_ms);
982
return true;
983
}
984
break;
985
case SPEED_TYPE_GROUNDSPEED:
986
gcs().send_text(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)speed_target_ms);
987
aparm.min_groundspeed.set(speed_target_ms);
988
return true;
989
990
case SPEED_TYPE_CLIMB_SPEED:
991
case SPEED_TYPE_DESCENT_SPEED:
992
case SPEED_TYPE_ENUM_END:
993
break;
994
}
995
996
if (throttle_pct > 0 && throttle_pct <= 100) {
997
gcs().send_text(MAV_SEVERITY_INFO, "Set throttle %u", (unsigned)throttle_pct);
998
aparm.throttle_cruise.set(throttle_pct);
999
return true;
1000
}
1001
1002
return false;
1003
}
1004
1005
void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)
1006
{
1007
if (cmd.p1 == 1 && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
1008
if (!set_home_persistently(gps.location())) {
1009
// silently ignore error
1010
}
1011
} else {
1012
if (!AP::ahrs().set_home(cmd.content.location)) {
1013
// silently ignore failure
1014
}
1015
}
1016
}
1017
1018
// start_command_callback - callback function called from ap-mission when it begins a new mission command
1019
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
1020
bool Plane::start_command_callback(const AP_Mission::Mission_Command &cmd)
1021
{
1022
if (control_mode == &mode_auto) {
1023
return start_command(cmd);
1024
}
1025
return true;
1026
}
1027
1028
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
1029
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
1030
bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)
1031
{
1032
if (control_mode == &mode_auto) {
1033
bool cmd_complete = verify_command(cmd);
1034
1035
// send message to GCS
1036
if (cmd_complete) {
1037
gcs().send_mission_item_reached_message(cmd.index);
1038
}
1039
1040
return cmd_complete;
1041
}
1042
return false;
1043
}
1044
1045
// exit_mission_callback - callback function called from ap-mission when the mission has completed
1046
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
1047
void Plane::exit_mission_callback()
1048
{
1049
if (control_mode == &mode_auto) {
1050
set_mode(mode_rtl, ModeReason::MISSION_END);
1051
gcs().send_text(MAV_SEVERITY_INFO, "Mission complete, changing mode to RTL");
1052
}
1053
}
1054
1055
#if HAL_QUADPLANE_ENABLED
1056
bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
1057
{
1058
const float radius = is_zero(quadplane.fw_land_approach_radius_m)? aparm.loiter_radius : quadplane.fw_land_approach_radius_m;
1059
const int8_t direction = is_negative(radius) ? -1 : 1;
1060
const float abs_radius = fabsf(radius);
1061
1062
loiter.direction = direction;
1063
1064
switch (vtol_approach_s.approach_stage) {
1065
case VTOLApproach::Stage::RTL:
1066
{
1067
// fly home and loiter at RTL alt
1068
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
1069
if (plane.reached_loiter_target()) {
1070
// descend to Q RTL alt
1071
plane.do_RTL(plane.home.alt + plane.quadplane.qrtl_alt_m*100UL);
1072
plane.loiter_angle_reset();
1073
vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT;
1074
}
1075
break;
1076
}
1077
case VTOLApproach::Stage::LOITER_TO_ALT:
1078
{
1079
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
1080
1081
if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_achieve_target_alt)) {
1082
Vector3f wind = ahrs.wind_estimate();
1083
vtol_approach_s.approach_direction_deg = degrees(atan2f(-wind.y, -wind.x));
1084
gcs().send_text(MAV_SEVERITY_INFO, "Selected an approach path of %.1f", (double)vtol_approach_s.approach_direction_deg);
1085
vtol_approach_s.approach_stage = VTOLApproach::Stage::ENSURE_RADIUS;
1086
}
1087
break;
1088
}
1089
case VTOLApproach::Stage::ENSURE_RADIUS:
1090
{
1091
// validate that the vehicle is at least the expected distance away from the loiter point
1092
// require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree
1093
if (((fabsF(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) &&
1094
(cmd.content.location.get_distance(current_loc) < abs_radius)) ||
1095
(labs(loiter.sum_cd) < 2)) {
1096
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
1097
break;
1098
}
1099
vtol_approach_s.approach_stage = VTOLApproach::Stage::WAIT_FOR_BREAKOUT;
1100
FALLTHROUGH;
1101
}
1102
case VTOLApproach::Stage::WAIT_FOR_BREAKOUT:
1103
{
1104
nav_controller->update_loiter(cmd.content.location, radius, direction);
1105
1106
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));
1107
1108
// breakout when within 5 degrees of the opposite direction
1109
if (fabsF(wrap_PI(ahrs.get_yaw_rad() - breakout_direction_rad)) < radians(5.0f)) {
1110
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
1111
vtol_approach_s.approach_stage = VTOLApproach::Stage::APPROACH_LINE;
1112
set_next_WP(cmd.content.location);
1113
// fallthrough
1114
} else {
1115
break;
1116
}
1117
FALLTHROUGH;
1118
}
1119
case VTOLApproach::Stage::APPROACH_LINE:
1120
{
1121
// project an approach path
1122
Location start = cmd.content.location;
1123
Location end = cmd.content.location;
1124
1125
// project a 1km waypoint to either side of the landing location
1126
start.offset_bearing(vtol_approach_s.approach_direction_deg + 180, 1000);
1127
end.offset_bearing(vtol_approach_s.approach_direction_deg, 1000);
1128
1129
nav_controller->update_waypoint(start, end);
1130
1131
// check if we should move on to the next waypoint
1132
Location breakout_stopping_loc = cmd.content.location;
1133
breakout_stopping_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, quadplane.stopping_distance_m());
1134
const bool past_finish_line = current_loc.past_interval_finish_line(start, breakout_stopping_loc);
1135
1136
Location breakout_loc = cmd.content.location;
1137
breakout_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, abs_radius);
1138
const bool half_radius = current_loc.line_path_proportion(breakout_loc, cmd.content.location) > 0.5;
1139
bool lined_up = true;
1140
Vector3f vel_NED;
1141
if (ahrs.get_velocity_NED(vel_NED)) {
1142
const Vector2f target_vec = current_loc.get_distance_NE(cmd.content.location);
1143
const float angle_err = fabsf(wrap_180(degrees(vel_NED.xy().angle(target_vec))));
1144
lined_up = (angle_err < 30);
1145
}
1146
1147
if (past_finish_line && (lined_up || half_radius)) {
1148
vtol_approach_s.approach_stage = VTOLApproach::Stage::VTOL_LANDING;
1149
quadplane.do_vtol_land(cmd);
1150
// fallthrough
1151
} else {
1152
break;
1153
}
1154
FALLTHROUGH;
1155
}
1156
case VTOLApproach::Stage::VTOL_LANDING:
1157
// nothing to do here, we should be into the quadplane landing code
1158
return true;
1159
}
1160
1161
return false;
1162
}
1163
#endif // HAL_QUADPLANE_ENABLED
1164
1165
bool Plane::verify_loiter_heading(bool init)
1166
{
1167
#if HAL_QUADPLANE_ENABLED
1168
if (quadplane.in_vtol_auto()) {
1169
// skip heading verify if in VTOL auto
1170
return true;
1171
}
1172
#endif
1173
1174
#if MODE_AUTOLAND_ENABLED
1175
if (control_mode == &mode_autoland) {
1176
// autoland mode has its own lineup criterion
1177
return mode_autoland.landing_lined_up();
1178
}
1179
#endif
1180
1181
//Get the lat/lon of next Nav waypoint after this one:
1182
AP_Mission::Mission_Command next_nav_cmd;
1183
if (! mission.get_next_nav_cmd(mission.get_current_nav_index() + 1,
1184
next_nav_cmd)) {
1185
//no next waypoint to shoot for -- go ahead and break out of loiter
1186
return true;
1187
}
1188
1189
if (init) {
1190
loiter.sum_cd = 0;
1191
}
1192
1193
return plane.mode_loiter.isHeadingLinedUp(next_WP_loc, next_nav_cmd.content.location);
1194
}
1195
1196
float Plane::get_wp_radius() const
1197
{
1198
#if HAL_QUADPLANE_ENABLED
1199
if (plane.quadplane.in_vtol_mode()) {
1200
return plane.quadplane.wp_nav->get_wp_radius_m();
1201
}
1202
#endif
1203
return g.waypoint_radius;
1204
}
1205
1206
#if AP_SCRIPTING_ENABLED
1207
/*
1208
support for scripted navigation, with verify operation for completion
1209
*/
1210
void Plane::do_nav_script_time(const AP_Mission::Mission_Command& cmd)
1211
{
1212
nav_scripting.enabled = true;
1213
nav_scripting.id++;
1214
nav_scripting.start_ms = AP_HAL::millis();
1215
nav_scripting.current_ms = nav_scripting.start_ms;
1216
1217
// start with current roll rate, pitch rate and throttle
1218
nav_scripting.roll_rate_dps = plane.rollController.get_pid_info().target;
1219
nav_scripting.pitch_rate_dps = plane.pitchController.get_pid_info().target;
1220
nav_scripting.yaw_rate_dps = degrees(ahrs.get_gyro().z);
1221
nav_scripting.throttle_pct = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
1222
}
1223
1224
/*
1225
wait for scripting to say that the mission item is complete
1226
*/
1227
bool Plane::verify_nav_script_time(const AP_Mission::Mission_Command& cmd)
1228
{
1229
if (cmd.content.nav_script_time.timeout_s > 0) {
1230
const uint32_t now = AP_HAL::millis();
1231
if (now - nav_scripting.start_ms > cmd.content.nav_script_time.timeout_s*1000U) {
1232
gcs().send_text(MAV_SEVERITY_INFO, "NavScriptTime timed out");
1233
nav_scripting.enabled = false;
1234
nav_scripting.rudder_offset_pct = 0;
1235
nav_scripting.run_yaw_rate_controller = true;
1236
}
1237
}
1238
return !nav_scripting.enabled;
1239
}
1240
1241
// check if we are in a NAV_SCRIPT_* command
1242
bool Plane::nav_scripting_active(void)
1243
{
1244
if (nav_scripting.enabled && AP_HAL::millis() - nav_scripting.current_ms > 1000) {
1245
// set_target_throttle_rate_rpy has not been called from script in last 1000ms
1246
nav_scripting.enabled = false;
1247
nav_scripting.current_ms = 0;
1248
nav_scripting.rudder_offset_pct = 0;
1249
nav_scripting.run_yaw_rate_controller = true;
1250
gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out");
1251
}
1252
if (control_mode == &mode_auto &&
1253
mission.get_current_nav_cmd().id != MAV_CMD_NAV_SCRIPT_TIME) {
1254
nav_scripting.enabled = false;
1255
}
1256
return nav_scripting.enabled;
1257
}
1258
1259
// support for NAV_SCRIPTING mission command
1260
bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
1261
{
1262
if (!nav_scripting_active()) {
1263
// not in NAV_SCRIPT_TIME
1264
return false;
1265
}
1266
const auto &c = mission.get_current_nav_cmd().content.nav_script_time;
1267
id = nav_scripting.id;
1268
cmd = c.command;
1269
arg1 = c.arg1.get();
1270
arg2 = c.arg2.get();
1271
arg3 = c.arg3;
1272
arg4 = c.arg4;
1273
return true;
1274
}
1275
1276
// called when script has completed the command
1277
void Plane::nav_script_time_done(uint16_t id)
1278
{
1279
if (id == nav_scripting.id) {
1280
nav_scripting.enabled = false;
1281
}
1282
}
1283
1284
// support for NAV_SCRIPTING mission command and aerobatics in other allowed modes
1285
void Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps)
1286
{
1287
nav_scripting.roll_rate_dps = constrain_float(roll_rate_dps, -g.acro_roll_rate, g.acro_roll_rate);
1288
nav_scripting.pitch_rate_dps = constrain_float(pitch_rate_dps, -g.acro_pitch_rate, g.acro_pitch_rate);
1289
nav_scripting.yaw_rate_dps = constrain_float(yaw_rate_dps, -g.acro_yaw_rate, g.acro_yaw_rate);
1290
nav_scripting.throttle_pct = constrain_float(throttle_pct, aparm.throttle_min, aparm.throttle_max);
1291
nav_scripting.current_ms = AP_HAL::millis();
1292
}
1293
1294
// support for rudder offset override in aerobatic scripting
1295
void Plane::set_rudder_offset(float rudder_pct, bool run_yaw_rate_controller)
1296
{
1297
nav_scripting.rudder_offset_pct = rudder_pct;
1298
nav_scripting.run_yaw_rate_controller = run_yaw_rate_controller;
1299
}
1300
1301
// enable NAV_SCRIPTING takeover in modes other than AUTO using script time mission commands
1302
bool Plane::nav_scripting_enable(uint8_t mode)
1303
{
1304
uint8_t current_control_mode = control_mode->mode_number();
1305
if (current_control_mode == mode) {
1306
switch (current_control_mode) {
1307
case Mode::Number::CIRCLE:
1308
case Mode::Number::STABILIZE:
1309
case Mode::Number::ACRO:
1310
case Mode::Number::FLY_BY_WIRE_A:
1311
case Mode::Number::FLY_BY_WIRE_B:
1312
case Mode::Number::CRUISE:
1313
case Mode::Number::LOITER:
1314
nav_scripting.enabled = true;
1315
nav_scripting.current_ms = AP_HAL::millis();
1316
break;
1317
default:
1318
nav_scripting.enabled = false;
1319
}
1320
} else {
1321
nav_scripting.enabled = false;
1322
}
1323
return nav_scripting.enabled;
1324
}
1325
#endif // AP_SCRIPTING_ENABLED
1326
1327
/*
1328
return true if this is a LAND command
1329
note that we consider a PAYLOAD_PLACE to be a land command as it
1330
follows the landing logic for quadplanes
1331
*/
1332
bool Plane::is_land_command(uint16_t command) const
1333
{
1334
return
1335
command == MAV_CMD_NAV_VTOL_LAND ||
1336
command == MAV_CMD_NAV_LAND ||
1337
command == MAV_CMD_NAV_PAYLOAD_PLACE;
1338
}
1339
1340
/*
1341
return true if in a specific AUTO mission command
1342
*/
1343
bool Plane::in_auto_mission_id(uint16_t command) const
1344
{
1345
return control_mode == &mode_auto && mission.get_current_nav_id() == command;
1346
}
1347
1348
1349