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