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