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/Rover/mode.h
Views: 1798
1
#pragma once
2
3
#include "Rover.h"
4
5
// pre-define ModeRTL so Auto can appear higher in this file
6
class ModeRTL;
7
8
class Mode
9
{
10
public:
11
12
// Auto Pilot modes
13
// ----------------
14
enum class Number : uint8_t {
15
MANUAL = 0,
16
ACRO = 1,
17
STEERING = 3,
18
HOLD = 4,
19
LOITER = 5,
20
FOLLOW = 6,
21
SIMPLE = 7,
22
#if MODE_DOCK_ENABLED
23
DOCK = 8,
24
#endif
25
CIRCLE = 9,
26
AUTO = 10,
27
RTL = 11,
28
SMART_RTL = 12,
29
GUIDED = 15,
30
INITIALISING = 16,
31
// Mode number 30 reserved for "offboard" for external/lua control.
32
};
33
34
// Constructor
35
Mode();
36
37
// do not allow copying
38
CLASS_NO_COPY(Mode);
39
40
// enter this mode, returns false if we failed to enter
41
bool enter();
42
43
// perform any cleanups required:
44
void exit();
45
46
// returns a unique number specific to this mode
47
virtual Number mode_number() const = 0;
48
49
// returns short text name (up to 4 bytes)
50
virtual const char *name4() const = 0;
51
52
//
53
// methods that sub classes should override to affect movement of the vehicle in this mode
54
//
55
56
// convert user input to targets, implement high level control for this mode
57
virtual void update() = 0;
58
59
//
60
// attributes of the mode
61
//
62
63
// return if in non-manual mode : Auto, Guided, RTL, SmartRTL
64
virtual bool is_autopilot_mode() const { return false; }
65
66
// return if external control is allowed in this mode (Guided or Guided-within-Auto)
67
virtual bool in_guided_mode() const { return false; }
68
69
// returns true if vehicle can be armed or disarmed from the transmitter in this mode
70
virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }
71
72
// returns false if vehicle cannot be armed in this mode
73
virtual bool allows_arming() const { return true; }
74
75
bool allows_stick_mixing() const { return is_autopilot_mode(); }
76
77
//
78
// attributes for mavlink system status reporting
79
//
80
81
// returns true if any RC input is used
82
virtual bool has_manual_input() const { return false; }
83
84
// true if heading is controlled
85
virtual bool attitude_stabilized() const { return true; }
86
87
// true if mode requires position and/or velocity estimate
88
virtual bool requires_position() const { return true; }
89
virtual bool requires_velocity() const { return true; }
90
91
// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
92
virtual float wp_bearing() const;
93
virtual float nav_bearing() const;
94
virtual float crosstrack_error() const;
95
virtual float get_desired_lat_accel() const;
96
97
// get speed error in m/s, not currently supported
98
float speed_error() const { return 0.0f; }
99
100
//
101
// navigation methods
102
//
103
104
// return distance (in meters) to destination
105
virtual float get_distance_to_destination() const { return 0.0f; }
106
107
// return desired location (used in Guided, Auto, RTL, etc)
108
// return true on success, false if there is no valid destination
109
virtual bool get_desired_location(Location& destination) const WARN_IF_UNUSED { return false; }
110
111
// set desired location (used in Guided, Auto)
112
// set next_destination (if known). If not provided vehicle stops at destination
113
virtual bool set_desired_location(const Location &destination, Location next_destination = Location()) WARN_IF_UNUSED;
114
115
// true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck
116
virtual bool reached_destination() const { return true; }
117
118
// get default speed for this mode (held in CRUISE_SPEED, WP_SPEED or RTL_SPEED)
119
// rtl argument should be true if called from RTL or SmartRTL modes (handled here to avoid duplication)
120
float get_speed_default(bool rtl = false) const;
121
122
// set desired speed in m/s
123
virtual bool set_desired_speed(float speed) { return false; }
124
125
// execute the mission in reverse (i.e. backing up)
126
void set_reversed(bool value);
127
128
// init reversed flag for autopilot mode
129
virtual void init_reversed_flag() { if (is_autopilot_mode()) { set_reversed(false); } }
130
131
// handle tacking request (from auxiliary switch) in sailboats
132
virtual void handle_tack_request();
133
134
protected:
135
136
// subclasses override this to perform checks before entering the mode
137
virtual bool _enter() { return true; }
138
139
// subclasses override this to perform any required cleanup when exiting the mode
140
virtual void _exit() { return; }
141
142
// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments
143
// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise
144
// throttle_out is in the range -100 ~ +100
145
void get_pilot_desired_steering_and_throttle(float &steering_out, float &throttle_out) const;
146
147
// decode pilot input steering and return steering_out and speed_out (in m/s)
148
void get_pilot_desired_steering_and_speed(float &steering_out, float &speed_out) const;
149
150
// decode pilot lateral movement input and return in lateral_out argument
151
void get_pilot_desired_lateral(float &lateral_out) const;
152
153
// decode pilot's input and return heading_out (in cd) and speed_out (in m/s)
154
void get_pilot_desired_heading_and_speed(float &heading_out, float &speed_out) const;
155
156
// decode pilot roll and pitch inputs and return in roll_out and pitch_out arguments
157
// outputs are in the range -1 to +1
158
void get_pilot_desired_roll_and_pitch(float &roll_out, float &pitch_out) const;
159
160
// decode pilot height inputs and return in height_out arguments
161
// outputs are in the range -1 to +1
162
void get_pilot_desired_walking_height(float &walking_height_out) const;
163
164
// high level call to navigate to waypoint
165
void navigate_to_waypoint();
166
167
// calculate steering output given a turn rate
168
// desired turn rate in radians/sec. Positive to the right.
169
void calc_steering_from_turn_rate(float turn_rate);
170
171
// calculate steering angle given a desired lateral acceleration
172
void calc_steering_from_lateral_acceleration(float lat_accel, bool reversed = false);
173
174
// calculate steering output to drive towards desired heading
175
// rate_max is a maximum turn rate in deg/s. set to zero to use default turn rate limits
176
void calc_steering_to_heading(float desired_heading_cd, float rate_max_degs = 0.0f);
177
178
// calculates the amount of throttle that should be output based
179
// on things like proximity to corners and current speed
180
virtual void calc_throttle(float target_speed, bool avoidance_enabled);
181
182
// performs a controlled stop. returns true once vehicle has stopped
183
bool stop_vehicle();
184
185
// estimate maximum vehicle speed (in m/s)
186
// cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1
187
float calc_speed_max(float cruise_speed, float cruise_throttle) const;
188
189
// calculate pilot input to nudge speed up or down
190
// target_speed should be in meters/sec
191
// reversed should be true if the vehicle is intentionally backing up which allows the pilot to increase the backing up speed by pulling the throttle stick down
192
float calc_speed_nudge(float target_speed, bool reversed);
193
194
protected:
195
196
// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments
197
// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise
198
// throttle_out is in the range -100 ~ +100
199
void get_pilot_input(float &steering_out, float &throttle_out) const;
200
void set_steering(float steering_value);
201
202
// references to avoid code churn:
203
class AP_AHRS &ahrs;
204
class Parameters &g;
205
class ParametersG2 &g2;
206
class RC_Channel *&channel_steer;
207
class RC_Channel *&channel_throttle;
208
class RC_Channel *&channel_lateral;
209
class RC_Channel *&channel_roll;
210
class RC_Channel *&channel_pitch;
211
class RC_Channel *&channel_walking_height;
212
class AR_AttitudeControl &attitude_control;
213
214
// private members for waypoint navigation
215
float _distance_to_destination; // distance from vehicle to final destination in meters
216
bool _reached_destination; // true once the vehicle has reached the destination
217
float _desired_yaw_cd; // desired yaw in centi-degrees. used in Auto, Guided and Loiter
218
};
219
220
221
class ModeAcro : public Mode
222
{
223
public:
224
225
Number mode_number() const override { return Number::ACRO; }
226
const char *name4() const override { return "ACRO"; }
227
228
// methods that affect movement of the vehicle in this mode
229
void update() override;
230
231
// attributes for mavlink system status reporting
232
bool has_manual_input() const override { return true; }
233
234
// acro mode requires a velocity estimate for non skid-steer rovers
235
bool requires_position() const override { return false; }
236
bool requires_velocity() const override;
237
238
// sailboats in acro mode support user manually initiating tacking from transmitter
239
void handle_tack_request() override;
240
};
241
242
243
class ModeAuto : public Mode
244
{
245
public:
246
247
Number mode_number() const override { return Number::AUTO; }
248
const char *name4() const override { return "AUTO"; }
249
250
// methods that affect movement of the vehicle in this mode
251
void update() override;
252
void calc_throttle(float target_speed, bool avoidance_enabled) override;
253
254
// attributes of the mode
255
bool is_autopilot_mode() const override { return true; }
256
257
// return if external control is allowed in this mode (Guided or Guided-within-Auto)
258
bool in_guided_mode() const override { return _submode == SubMode::Guided || _submode == SubMode::NavScriptTime; }
259
260
// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
261
float wp_bearing() const override;
262
float nav_bearing() const override;
263
float crosstrack_error() const override;
264
float get_desired_lat_accel() const override;
265
266
// return distance (in meters) to destination
267
float get_distance_to_destination() const override;
268
269
// get or set desired location
270
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
271
bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED;
272
bool reached_destination() const override;
273
274
// set desired speed in m/s
275
bool set_desired_speed(float speed) override;
276
277
// start RTL (within auto)
278
void start_RTL();
279
280
// lua accessors for nav script time support
281
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4);
282
void nav_script_time_done(uint16_t id);
283
284
//
285
void init_reversed_flag() override {
286
if (!mission.is_resume()) {
287
set_reversed(false);
288
}
289
}
290
291
AP_Mission mission{
292
FUNCTOR_BIND_MEMBER(&ModeAuto::start_command, bool, const AP_Mission::Mission_Command&),
293
FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&),
294
FUNCTOR_BIND_MEMBER(&ModeAuto::exit_mission, void)};
295
296
enum class DoneBehaviour : uint8_t {
297
HOLD = 0,
298
LOITER = 1,
299
ACRO = 2,
300
MANUAL = 3,
301
};
302
303
protected:
304
305
bool _enter() override;
306
void _exit() override;
307
308
enum SubMode: uint8_t {
309
WP, // drive to a given location
310
HeadingAndSpeed, // turn to a given heading
311
RTL, // perform RTL within auto mode
312
Loiter, // perform Loiter within auto mode
313
Guided, // handover control to external navigation system from within auto mode
314
Stop, // stop the vehicle as quickly as possible
315
NavScriptTime, // accept targets from lua scripts while NAV_SCRIPT_TIME commands are executing
316
Circle, // circle a given location
317
} _submode;
318
319
private:
320
321
bool check_trigger(void);
322
bool start_loiter();
323
void start_guided(const Location& target_loc);
324
void start_stop();
325
void send_guided_position_target();
326
327
bool start_command(const AP_Mission::Mission_Command& cmd);
328
void exit_mission();
329
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
330
331
bool verify_command(const AP_Mission::Mission_Command& cmd);
332
void do_RTL(void);
333
bool do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination);
334
void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
335
void do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd);
336
void do_nav_delay(const AP_Mission::Mission_Command& cmd);
337
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
338
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
339
bool verify_RTL() const;
340
bool verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd);
341
bool verify_loiter_time(const AP_Mission::Mission_Command& cmd);
342
bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
343
bool verify_nav_set_yaw_speed();
344
bool do_circle(const AP_Mission::Mission_Command& cmd);
345
bool verify_circle(const AP_Mission::Mission_Command& cmd);
346
void do_wait_delay(const AP_Mission::Mission_Command& cmd);
347
void do_within_distance(const AP_Mission::Mission_Command& cmd);
348
bool verify_wait_delay();
349
bool verify_within_distance();
350
void do_change_speed(const AP_Mission::Mission_Command& cmd);
351
void do_set_home(const AP_Mission::Mission_Command& cmd);
352
void do_set_reverse(const AP_Mission::Mission_Command& cmd);
353
void do_guided_limits(const AP_Mission::Mission_Command& cmd);
354
#if AP_SCRIPTING_ENABLED
355
void do_nav_script_time(const AP_Mission::Mission_Command& cmd);
356
bool verify_nav_script_time();
357
#endif
358
359
bool waiting_to_start; // true if waiting for EKF origin before starting mission
360
bool auto_triggered; // true when auto has been triggered to start
361
362
// HeadingAndSpeed sub mode variables
363
float _desired_speed; // desired speed in HeadingAndSpeed submode
364
bool _reached_heading; // true when vehicle has reached desired heading in TurnToHeading sub mode
365
366
// Loiter control
367
uint16_t loiter_duration; // How long we should loiter at the nav_waypoint (time in seconds)
368
uint32_t loiter_start_time; // How long have we been loitering - The start time in millis
369
bool previously_reached_wp; // set to true if we have EVER reached the waypoint
370
371
// Guided-within-Auto variables
372
struct {
373
Location loc; // location target sent to external navigation
374
bool valid; // true if loc is valid
375
uint32_t last_sent_ms; // system time that target was last sent to offboard navigation
376
} guided_target;
377
378
// Conditional command
379
// A value used in condition commands (eg delay, change alt, etc.)
380
// For example in a change altitude command, it is the altitude to change to.
381
int32_t condition_value;
382
// A starting value used to check the status of a conditional command.
383
// For example in a delay command the condition_start records that start time for the delay
384
int32_t condition_start;
385
386
// Delay the next navigation command
387
uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands
388
uint32_t nav_delay_time_start_ms;
389
390
#if AP_SCRIPTING_ENABLED
391
// nav_script_time command variables
392
struct {
393
bool done; // true once lua script indicates it has completed
394
uint16_t id; // unique id to avoid race conditions between commands and lua scripts
395
uint32_t start_ms; // system time nav_script_time command was received (used for timeout)
396
uint8_t command; // command number provided by mission command
397
uint8_t timeout_s; // timeout (in seconds) provided by mission command
398
float arg1; // 1st argument provided by mission command
399
float arg2; // 2nd argument provided by mission command
400
int16_t arg3; // 3rd argument provided by mission command
401
int16_t arg4; // 4th argument provided by mission command
402
} nav_scripting;
403
#endif
404
405
// Mission change detector
406
AP_Mission_ChangeDetector mis_change_detector;
407
};
408
409
class ModeCircle : public Mode
410
{
411
public:
412
413
// need a constructor for parameters
414
ModeCircle();
415
416
// Does not allow copies
417
CLASS_NO_COPY(ModeCircle);
418
419
Number mode_number() const override { return Number::CIRCLE; }
420
const char *name4() const override { return "CIRC"; }
421
422
// initialise with specific center location, radius (in meters) and direction
423
// replaces use of _enter when initialised from within Auto mode
424
bool set_center(const Location& center_loc, float radius_m, bool dir_ccw);
425
426
// methods that affect movement of the vehicle in this mode
427
void update() override;
428
429
bool is_autopilot_mode() const override { return true; }
430
431
// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
432
float wp_bearing() const override;
433
float nav_bearing() const override;
434
float crosstrack_error() const override { return dist_to_edge_m; }
435
float get_desired_lat_accel() const override;
436
437
// set desired speed in m/s
438
bool set_desired_speed(float speed_ms) override;
439
440
// return distance (in meters) to destination
441
float get_distance_to_destination() const override { return _distance_to_destination; }
442
443
// get or set desired location
444
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
445
446
// return total angle in radians that vehicle has circled
447
// fabsf is used so that full rotations in either direction are counted
448
float get_angle_total_rad() const { return fabsf(angle_total_rad); }
449
450
static const struct AP_Param::GroupInfo var_info[];
451
452
protected:
453
454
AP_Float radius; // circle radius in meters
455
AP_Float speed; // vehicle speed in m/s. If zero uses WP_SPEED
456
AP_Int8 direction; // direction 0:clockwise, 1:counter-clockwise
457
458
// initialise mode
459
bool _enter() override;
460
461
// Update position controller targets driving to the circle edge
462
void update_drive_to_radius();
463
464
// Update position controller targets while circling
465
void update_circling();
466
467
// initialise target_yaw_rad using the vehicle's position and yaw
468
// if there is no current position estimate target_yaw_rad is set to vehicle yaw
469
void init_target_yaw_rad();
470
471
// limit config speed so that lateral acceleration is within limits
472
// outputs warning to user if speed is reduced
473
void check_config_speed();
474
475
// ensure config radius is no smaller then vehicle's TURN_RADIUS
476
// radius is increased if necessary and warning is output to the user
477
void check_config_radius();
478
479
// enum for Direction parameter
480
enum class Direction {
481
CW = 0,
482
CCW = 1
483
};
484
485
// local members
486
struct {
487
Location center_loc; // circle center as a Location
488
Vector2f center_pos; // circle center as an offset (in meters) from the EKF origin
489
float radius; // circle radius
490
float speed; // desired speed around circle in m/s
491
Direction dir; // direction, 0:clockwise, 1:counter-clockwise
492
} config;
493
struct {
494
float speed; // vehicle's target speed around circle in m/s
495
float yaw_rad; // earth-frame angle of tarrget point on the circle
496
Vector2p pos; // latest position target sent to position controller
497
Vector2f vel; // latest velocity target sent to position controller
498
Vector2f accel; // latest accel target sent to position controller
499
} target;
500
float angle_total_rad; // total angle in radians that vehicle has circled
501
bool reached_edge; // true once vehicle has reached edge of circle
502
float dist_to_edge_m; // distance to edge of circle in meters (equivalent to crosstrack error)
503
bool tracking_back; // true if the vehicle is trying to track back onto the circle
504
};
505
506
class ModeGuided : public Mode
507
{
508
public:
509
#if AP_EXTERNAL_CONTROL_ENABLED
510
friend class AP_ExternalControl_Rover;
511
#endif
512
513
Number mode_number() const override { return Number::GUIDED; }
514
const char *name4() const override { return "GUID"; }
515
516
// methods that affect movement of the vehicle in this mode
517
void update() override;
518
519
// attributes of the mode
520
bool is_autopilot_mode() const override { return true; }
521
522
// return if external control is allowed in this mode (Guided or Guided-within-Auto)
523
bool in_guided_mode() const override { return true; }
524
525
// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
526
float wp_bearing() const override;
527
float nav_bearing() const override;
528
float crosstrack_error() const override;
529
float get_desired_lat_accel() const override;
530
531
// return distance (in meters) to destination
532
float get_distance_to_destination() const override;
533
534
// return true if vehicle has reached destination
535
bool reached_destination() const override;
536
537
// set desired speed in m/s
538
bool set_desired_speed(float speed) override;
539
540
// get or set desired location
541
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
542
bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED;
543
544
// set desired heading and speed
545
void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed);
546
547
// set desired heading-delta, turn-rate and speed
548
void set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed);
549
void set_desired_turn_rate_and_speed(float turn_rate_cds, float target_speed);
550
551
// set steering and throttle (-1 to +1). Only called from scripts
552
void set_steering_and_throttle(float steering, float throttle);
553
554
// vehicle start loiter
555
bool start_loiter();
556
557
// start stopping
558
void start_stop();
559
560
// guided limits
561
void limit_set(uint32_t timeout_ms, float horiz_max);
562
void limit_clear();
563
void limit_init_time_and_location();
564
bool limit_breached() const;
565
566
protected:
567
568
enum class SubMode: uint8_t {
569
WP,
570
HeadingAndSpeed,
571
TurnRateAndSpeed,
572
Loiter,
573
SteeringAndThrottle,
574
Stop
575
};
576
577
// enum for GUID_OPTIONS parameter
578
enum class Options : int32_t {
579
SCurvesUsedForNavigation = (1U << 6)
580
};
581
582
bool _enter() override;
583
584
// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping
585
// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping)
586
bool use_scurves_for_navigation() const;
587
588
SubMode _guided_mode; // stores which GUIDED mode the vehicle is in
589
590
// attitude control
591
bool have_attitude_target; // true if we have a valid attitude target
592
uint32_t _des_att_time_ms; // system time last call to set_desired_attitude was made (used for timeout)
593
float _desired_yaw_rate_cds;// target turn rate centi-degrees per second
594
bool send_notification; // used to send one time notification to ground station
595
float _desired_speed; // desired speed used only in HeadingAndSpeed submode
596
597
// direct steering and throttle control
598
bool _have_strthr; // true if we have a valid direct steering and throttle inputs
599
uint32_t _strthr_time_ms; // system time last call to set_steering_and_throttle was made (used for timeout)
600
float _strthr_steering; // direct steering input in the range -1 to +1
601
float _strthr_throttle; // direct throttle input in the range -1 to +1
602
603
// limits
604
struct {
605
uint32_t timeout_ms;// timeout from the time that guided is invoked
606
float horiz_max; // horizontal position limit in meters from where guided mode was initiated (0 = no limit)
607
uint32_t start_time_ms; // system time in milliseconds that control was handed to the external computer
608
Location start_loc; // starting location for checking horiz_max limit
609
} limit;
610
};
611
612
613
class ModeHold : public Mode
614
{
615
public:
616
617
Number mode_number() const override { return Number::HOLD; }
618
const char *name4() const override { return "HOLD"; }
619
620
// methods that affect movement of the vehicle in this mode
621
void update() override;
622
623
// attributes for mavlink system status reporting
624
bool attitude_stabilized() const override { return false; }
625
626
// hold mode does not require position or velocity estimate
627
bool requires_position() const override { return false; }
628
bool requires_velocity() const override { return false; }
629
};
630
631
class ModeLoiter : public Mode
632
{
633
public:
634
635
Number mode_number() const override { return Number::LOITER; }
636
const char *name4() const override { return "LOIT"; }
637
638
// methods that affect movement of the vehicle in this mode
639
void update() override;
640
641
// attributes of the mode
642
bool is_autopilot_mode() const override { return true; }
643
644
// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
645
float wp_bearing() const override { return _desired_yaw_cd * 0.01f; }
646
float nav_bearing() const override { return _desired_yaw_cd * 0.01f; }
647
float crosstrack_error() const override { return 0.0f; }
648
649
// return desired location
650
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
651
652
// return distance (in meters) to destination
653
float get_distance_to_destination() const override { return _distance_to_destination; }
654
655
protected:
656
657
bool _enter() override;
658
659
Location _destination; // target location to hold position around
660
float _desired_speed; // desired speed (ramped down from initial speed to zero)
661
};
662
663
class ModeManual : public Mode
664
{
665
public:
666
667
Number mode_number() const override { return Number::MANUAL; }
668
const char *name4() const override { return "MANU"; }
669
670
// methods that affect movement of the vehicle in this mode
671
void update() override;
672
673
// attributes for mavlink system status reporting
674
bool has_manual_input() const override { return true; }
675
bool attitude_stabilized() const override { return false; }
676
677
// manual mode does not require position or velocity estimate
678
bool requires_position() const override { return false; }
679
bool requires_velocity() const override { return false; }
680
681
protected:
682
683
void _exit() override;
684
};
685
686
687
class ModeRTL : public Mode
688
{
689
public:
690
691
Number mode_number() const override { return Number::RTL; }
692
const char *name4() const override { return "RTL"; }
693
694
// methods that affect movement of the vehicle in this mode
695
void update() override;
696
697
// attributes of the mode
698
bool is_autopilot_mode() const override { return true; }
699
700
// do not allow arming from this mode
701
bool allows_arming() const override { return false; }
702
703
// return desired location
704
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
705
706
// return distance (in meters) to destination
707
float get_distance_to_destination() const override { return _distance_to_destination; }
708
bool reached_destination() const override;
709
710
// set desired speed in m/s
711
bool set_desired_speed(float speed) override;
712
713
protected:
714
715
bool _enter() override;
716
717
bool send_notification; // used to send one time notification to ground station
718
bool _loitering; // true if loitering at end of RTL
719
720
};
721
722
class ModeSmartRTL : public Mode
723
{
724
public:
725
726
Number mode_number() const override { return Number::SMART_RTL; }
727
const char *name4() const override { return "SRTL"; }
728
729
// methods that affect movement of the vehicle in this mode
730
void update() override;
731
732
// attributes of the mode
733
bool is_autopilot_mode() const override { return true; }
734
735
// do not allow arming from this mode
736
bool allows_arming() const override { return false; }
737
738
// return desired location
739
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;
740
741
// return distance (in meters) to destination
742
float get_distance_to_destination() const override { return _distance_to_destination; }
743
bool reached_destination() const override { return smart_rtl_state == SmartRTLState::StopAtHome; }
744
745
// set desired speed in m/s
746
bool set_desired_speed(float speed) override;
747
748
// save current position for use by the smart_rtl flight mode
749
void save_position();
750
751
protected:
752
753
// Safe RTL states
754
enum class SmartRTLState: uint8_t {
755
WaitForPathCleanup,
756
PathFollow,
757
StopAtHome,
758
Failure
759
} smart_rtl_state;
760
761
bool _enter() override;
762
bool _load_point;
763
bool _loitering; // true if loitering at end of SRTL
764
};
765
766
767
768
class ModeSteering : public Mode
769
{
770
public:
771
772
Number mode_number() const override { return Number::STEERING; }
773
const char *name4() const override { return "STER"; }
774
775
// methods that affect movement of the vehicle in this mode
776
void update() override;
777
778
// attributes for mavlink system status reporting
779
bool has_manual_input() const override { return true; }
780
781
// steering requires velocity but not position
782
bool requires_position() const override { return false; }
783
bool requires_velocity() const override { return true; }
784
785
// return desired lateral acceleration
786
float get_desired_lat_accel() const override { return _desired_lat_accel; }
787
788
private:
789
790
float _desired_lat_accel; // desired lateral acceleration calculated from pilot steering input
791
};
792
793
class ModeInitializing : public Mode
794
{
795
public:
796
797
Number mode_number() const override { return Number::INITIALISING; }
798
const char *name4() const override { return "INIT"; }
799
800
// methods that affect movement of the vehicle in this mode
801
void update() override { }
802
803
// do not allow arming from this mode
804
bool allows_arming() const override { return false; }
805
806
// attributes for mavlink system status reporting
807
bool has_manual_input() const override { return true; }
808
bool attitude_stabilized() const override { return false; }
809
protected:
810
bool _enter() override { return false; };
811
};
812
813
#if MODE_FOLLOW_ENABLED
814
class ModeFollow : public Mode
815
{
816
public:
817
818
Number mode_number() const override { return Number::FOLLOW; }
819
const char *name4() const override { return "FOLL"; }
820
821
// methods that affect movement of the vehicle in this mode
822
void update() override;
823
824
// attributes of the mode
825
bool is_autopilot_mode() const override { return true; }
826
827
// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
828
float wp_bearing() const override;
829
float nav_bearing() const override { return wp_bearing(); }
830
float crosstrack_error() const override { return 0.0f; }
831
832
// return desired location
833
bool get_desired_location(Location& destination) const override WARN_IF_UNUSED { return false; }
834
835
// return distance (in meters) to destination
836
float get_distance_to_destination() const override;
837
838
// set desired speed in m/s
839
bool set_desired_speed(float speed) override;
840
841
protected:
842
843
bool _enter() override;
844
void _exit() override;
845
846
float _desired_speed; // desired speed in m/s
847
};
848
#endif
849
850
class ModeSimple : public Mode
851
{
852
public:
853
854
Number mode_number() const override { return Number::SIMPLE; }
855
const char *name4() const override { return "SMPL"; }
856
857
// methods that affect movement of the vehicle in this mode
858
void update() override;
859
void init_heading();
860
861
// simple type enum used for SIMPLE_TYPE parameter
862
enum simple_type {
863
Simple_InitialHeading = 0,
864
Simple_CardinalDirections = 1,
865
};
866
867
private:
868
869
float _initial_heading_cd; // vehicle heading (in centi-degrees) at moment vehicle was armed
870
float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot
871
};
872
873
#if MODE_DOCK_ENABLED
874
class ModeDock : public Mode
875
{
876
public:
877
878
// need a constructor for parameters
879
ModeDock(void);
880
881
// Does not allow copies
882
CLASS_NO_COPY(ModeDock);
883
884
Number mode_number() const override { return Number::DOCK; }
885
const char *name4() const override { return "DOCK"; }
886
887
// methods that affect movement of the vehicle in this mode
888
void update() override;
889
890
bool is_autopilot_mode() const override { return true; }
891
892
// return distance (in meters) to destination
893
float get_distance_to_destination() const override { return _distance_to_destination; }
894
895
static const struct AP_Param::GroupInfo var_info[];
896
897
protected:
898
899
AP_Float speed; // dock mode speed
900
AP_Float desired_dir; // desired direction of approach
901
AP_Int8 hdg_corr_enable; // enable heading correction
902
AP_Float hdg_corr_weight; // heading correction weight
903
AP_Float stopping_dist; // how far away from the docking target should we start stopping
904
905
bool _enter() override;
906
907
// return reduced speed of vehicle based on error in position and current distance from the dock
908
float apply_slowdown(float desired_speed);
909
910
// calculate position of dock relative to the vehicle
911
bool calc_dock_pos_rel_vehicle_NE(Vector2f &dock_pos_rel_vehicle) const;
912
913
// we force the vehicle to use real dock target vector when this much close to the docking station
914
const float _force_real_target_limit_cm = 300.0f;
915
// acceptable lateral error in vehicle's position with respect to dock. This is used while slowing down the vehicle
916
const float _acceptable_pos_error_cm = 20.0f;
917
918
Vector2f _dock_pos_rel_origin_cm; // position vector towards docking target relative to ekf origin
919
Vector2f _desired_heading_NE; // unit vector in desired direction of docking
920
bool _docking_complete = false; // flag to mark docking complete when we are close enough to the dock
921
bool _loitering = false; // true if we are loitering after mission completion
922
};
923
#endif
924
925