APM:Copter
mode.h
Go to the documentation of this file.
1 #pragma once
2 
3 // this class is #included into the Copter:: namespace
4 
5 class Mode {
6  friend class Copter;
7  friend class AP_Arming_Copter;
8  friend class ToyMode;
9  friend class GCS_MAVLINK_Copter;
10 
11  // constructor
12  Mode(void);
13 
14 public:
15 
16  // Navigation Yaw control
17  class AutoYaw {
18 
19  public:
20 
21  // yaw(): main product of AutoYaw; the heading:
22  float yaw();
23 
24  // mode(): current method of determining desired yaw:
26  void set_mode_to_default(bool rtl);
27  void set_mode(autopilot_yaw_mode new_mode);
28  autopilot_yaw_mode default_mode(bool rtl) const;
29 
30  // rate_cds(): desired yaw rate in centidegrees/second:
31  float rate_cds() const;
32  void set_rate(float new_rate_cds);
33 
34  // set_roi(...): set a "look at" location:
35  void set_roi(const Location &roi_location);
36 
37  void set_fixed_yaw(float angle_deg,
38  float turn_rate_dps,
39  int8_t direction,
40  bool relative_angle);
41 
42  private:
43 
44  float look_ahead_yaw();
45  float roi_yaw();
46 
47  // auto flight mode's yaw mode
49 
50  // Yaw will point at this location if mode is set to AUTO_YAW_ROI
52 
53  // bearing from current location to the ROI
54  float _roi_yaw;
55 
56  // yaw used for YAW_FIXED yaw_mode
57  int32_t _fixed_yaw;
58 
59  // Deg/s we should turn
61 
62  // heading when in yaw_look_ahead_yaw
64 
65  // turn rate (in cds) when auto_yaw_mode is set to AUTO_YAW_RATE
66  float _rate_cds;
67 
68  // used to reduce update rate to 100hz:
69  uint8_t roi_yaw_counter;
70 
71  };
72  static AutoYaw auto_yaw;
73 
74 protected:
75 
76  virtual bool init(bool ignore_checks) = 0;
77  virtual void run() = 0;
78 
79  virtual bool is_autopilot() const { return false; }
80  virtual bool requires_GPS() const = 0;
81  virtual bool has_manual_throttle() const = 0;
82  virtual bool allows_arming(bool from_gcs) const = 0;
83 
84  virtual bool landing_gear_should_be_deployed() const { return false; }
85 
86  virtual const char *name() const = 0;
87 
88  // returns a string for this flightmode, exactly 4 bytes
89  virtual const char *name4() const = 0;
90 
91  // navigation support functions
92  void update_navigation();
93  virtual void run_autopilot() {}
94  virtual uint32_t wp_distance() const { return 0; }
95  virtual int32_t wp_bearing() const { return 0; }
96  virtual bool get_wp(Location_Class &loc) { return false; };
97  virtual bool in_guided_mode() const { return false; }
98 
99  // pilot input processing
100  void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const;
101 
102  // takeoff support
103  bool takeoff_triggered(float target_climb_rate) const;
104 
105  // helper functions
107 
108  // functions to control landing
109  // in modes that support landing
110  int32_t get_alt_above_ground(void);
112  void land_run_vertical_control(bool pause_descent = false);
113 
114  // convenience references to avoid code churn in conversion:
128  float &G_Dt;
129  ap_t ≈
130  takeoff_state_t &takeoff_state;
131 
132  // gnd speed limit required to observe optical flow sensor limits
134 
135  // scale factor applied to velocity controller gain to prevent optical flow noise causing excessive angle demand noise
137 
138 #if FRAME_CONFIG == HELI_FRAME
139  heli_flags_t &heli_flags;
140 #endif
141 
142  // pass-through functions to reduce code churn on conversion;
143  // these are candidates for moving into the Mode base
144  // class.
145  float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
146  float get_pilot_desired_yaw_rate(int16_t stick_angle);
147  float get_pilot_desired_climb_rate(float throttle_control);
148  float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid = 0.0f);
149  float get_non_takeoff_throttle(void);
150  void update_simple_mode(void);
152  void set_land_complete(bool b);
153  GCS_Copter &gcs();
154  void Log_Write_Event(uint8_t id);
155  void set_throttle_takeoff(void);
156  void takeoff_timer_start(float alt_cm);
157  void takeoff_stop(void);
158  void takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate);
159  float get_avoidance_adjusted_climbrate(float target_rate);
160  uint16_t get_pilot_speed_dn(void);
161 
162  // end pass-through functions
163 };
164 
165 
166 #if MODE_ACRO_ENABLED == ENABLED
167 class ModeAcro : public Mode {
168 
169 public:
170  // inherit constructor
171  using Copter::Mode::Mode;
172 
173  virtual bool init(bool ignore_checks) override;
174  virtual void run() override;
175 
176  bool is_autopilot() const override { return false; }
177  bool requires_GPS() const override { return false; }
178  bool has_manual_throttle() const override { return true; }
179  bool allows_arming(bool from_gcs) const override { return true; };
180 
181 protected:
182 
183  const char *name() const override { return "ACRO"; }
184  const char *name4() const override { return "ACRO"; }
185 
186  void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out);
187 
188 private:
189 
190 };
191 #endif
192 
193 #if FRAME_CONFIG == HELI_FRAME
194 class ModeAcro_Heli : public ModeAcro {
195 
196 public:
197  // inherit constructor
199 
200  bool init(bool ignore_checks) override;
201  void run() override;
202 
203 protected:
204 private:
205 };
206 #endif
207 
208 
209 class ModeAltHold : public Mode {
210 
211 public:
212  // inherit constructor
213  using Copter::Mode::Mode;
214 
215  bool init(bool ignore_checks) override;
216  void run() override;
217 
218  bool requires_GPS() const override { return false; }
219  bool has_manual_throttle() const override { return false; }
220  bool allows_arming(bool from_gcs) const override { return true; };
221  bool is_autopilot() const override { return false; }
222 
223 protected:
224 
225  const char *name() const override { return "ALT_HOLD"; }
226  const char *name4() const override { return "ALTH"; }
227 
228 private:
229 
230 };
231 
232 
233 class ModeAuto : public Mode {
234 
235 public:
236  // inherit constructor
237  using Copter::Mode::Mode;
238 
239  bool init(bool ignore_checks) override;
240  void run() override;
241 
242  bool is_autopilot() const override { return true; }
243  bool requires_GPS() const override { return true; }
244  bool has_manual_throttle() const override { return false; }
245  bool allows_arming(bool from_gcs) const override { return false; };
246  bool in_guided_mode() const { return mode() == Auto_NavGuided; }
247 
248  // Auto
249  AutoMode mode() const { return _mode; }
250 
251  bool loiter_start();
252  void rtl_start();
253  void takeoff_start(const Location& dest_loc);
254  void wp_start(const Vector3f& destination);
255  void wp_start(const Location_Class& dest_loc);
256  void land_start();
257  void land_start(const Vector3f& destination);
258  void circle_movetoedge_start(const Location_Class &circle_center, float radius_m);
259  void circle_start();
260  void spline_start(const Vector3f& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Vector3f& next_spline_destination);
261  void spline_start(const Location_Class& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location_Class& next_destination);
262  void nav_guided_start();
263 
264  bool landing_gear_should_be_deployed() const override;
265 
266  void payload_place_start();
267 
268  // only out here temporarily
269  bool start_command(const AP_Mission::Mission_Command& cmd);
270  bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
271  void exit_mission();
272 
273  // for GCS_MAVLink to call:
274  bool do_guided(const AP_Mission::Mission_Command& cmd);
275 
276 protected:
277 
278  const char *name() const override { return "AUTO"; }
279  const char *name4() const override { return "AUTO"; }
280 
281  uint32_t wp_distance() const override;
282  int32_t wp_bearing() const override;
283  bool get_wp(Location_Class &loc) override;
284  void run_autopilot() override;
285 
286 private:
287 
288  bool verify_command(const AP_Mission::Mission_Command& cmd);
289 
290  void takeoff_run();
291  void wp_run();
292  void spline_run();
293  void land_run();
294  void rtl_run();
295  void circle_run();
296  void nav_guided_run();
297  void loiter_run();
298 
299  void payload_place_start(const Vector3f& destination);
300  void payload_place_run();
301  bool payload_place_run_should_run();
302  void payload_place_run_loiter();
303  void payload_place_run_descend();
304  void payload_place_run_release();
305 
306  AutoMode _mode = Auto_TakeOff; // controls which auto controller is run
307 
308  Location_Class terrain_adjusted_location(const AP_Mission::Mission_Command& cmd) const;
309 
310  void do_takeoff(const AP_Mission::Mission_Command& cmd);
311  void do_nav_wp(const AP_Mission::Mission_Command& cmd);
312  void do_land(const AP_Mission::Mission_Command& cmd);
313  void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd);
314  void do_circle(const AP_Mission::Mission_Command& cmd);
315  void do_loiter_time(const AP_Mission::Mission_Command& cmd);
316  void do_spline_wp(const AP_Mission::Mission_Command& cmd);
317 #if NAV_GUIDED == ENABLED
318  void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
319  void do_guided_limits(const AP_Mission::Mission_Command& cmd);
320 #endif
321  void do_nav_delay(const AP_Mission::Mission_Command& cmd);
322  void do_wait_delay(const AP_Mission::Mission_Command& cmd);
323  void do_within_distance(const AP_Mission::Mission_Command& cmd);
324  void do_yaw(const AP_Mission::Mission_Command& cmd);
325  void do_change_speed(const AP_Mission::Mission_Command& cmd);
326  void do_set_home(const AP_Mission::Mission_Command& cmd);
327  void do_roi(const AP_Mission::Mission_Command& cmd);
328  void do_mount_control(const AP_Mission::Mission_Command& cmd);
329 #if CAMERA == ENABLED
330  void do_digicam_configure(const AP_Mission::Mission_Command& cmd);
331  void do_digicam_control(const AP_Mission::Mission_Command& cmd);
332 #endif
333 #if PARACHUTE == ENABLED
334  void do_parachute(const AP_Mission::Mission_Command& cmd);
335 #endif
336 #if GRIPPER_ENABLED == ENABLED
337  void do_gripper(const AP_Mission::Mission_Command& cmd);
338 #endif
339 #if WINCH_ENABLED == ENABLED
340  void do_winch(const AP_Mission::Mission_Command& cmd);
341 #endif
342  void do_payload_place(const AP_Mission::Mission_Command& cmd);
343  void do_RTL(void);
344 
345  bool verify_takeoff();
346  bool verify_land();
347  bool verify_payload_place();
348  bool verify_loiter_unlimited();
349  bool verify_loiter_time();
350  bool verify_RTL();
351  bool verify_wait_delay();
352  bool verify_within_distance();
353  bool verify_yaw();
354  bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
355  bool verify_circle(const AP_Mission::Mission_Command& cmd);
356  bool verify_spline_wp(const AP_Mission::Mission_Command& cmd);
357 #if NAV_GUIDED == ENABLED
358  bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
359 #endif
360  bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
361 
362  void auto_spline_start(const Location_Class& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location_Class& next_destination);
363 
364  // Loiter control
365  uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)
366  uint32_t loiter_time; // How long have we been loitering - The start time in millis
367 
368  // Delay the next navigation command
369  int32_t nav_delay_time_max; // used for delaying the navigation commands (eg land,takeoff etc.)
371 
372  // Delay Mission Scripting Command
373  int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
374  uint32_t condition_start;
375 
376  LandStateType land_state = LandStateType_FlyToLocation; // records state of land (flying to location, descending)
377 
378  struct {
379  PayloadPlaceStateType state = PayloadPlaceStateType_Calibrating_Hover_Start; // records state of place (descending, releasing, released, ...)
380  uint32_t hover_start_timestamp; // milliseconds
382  uint32_t descend_start_timestamp; // milliseconds
383  uint32_t place_start_timestamp; // milliseconds
386  float descend_max; // centimetres
387  } nav_payload_place;
388 
389 };
390 
391 #if AUTOTUNE_ENABLED == ENABLED
392 class ModeAutoTune : public Mode {
393 
394 public:
395  // inherit constructor
396  using Copter::Mode::Mode;
397 
398  bool init(bool ignore_checks) override;
399  void run() override;
400 
401  bool requires_GPS() const override { return false; }
402  bool has_manual_throttle() const override { return false; }
403  bool allows_arming(bool from_gcs) const override { return false; }
404  bool is_autopilot() const override { return false; }
405 
406  void save_tuning_gains();
407 
408  void stop();
409 
410 protected:
411 
412  const char *name() const override { return "AUTOTUNE"; }
413  const char *name4() const override { return "ATUN"; }
414 
415 private:
416 
417  bool start(bool ignore_checks);
418 
419  void autotune_attitude_control();
420  void backup_gains_and_initialise();
421  void load_orig_gains();
422  void load_tuned_gains();
423  void load_intra_test_gains();
424  void load_twitch_gains();
425  void update_gcs(uint8_t message_id);
426  bool roll_enabled();
427  bool pitch_enabled();
428  bool yaw_enabled();
429  void twitching_test_rate(float rate, float rate_target, float &meas_rate_min, float &meas_rate_max);
430  void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max);
431  void twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max);
432  void updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
433  void updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
434  void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
435  void updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
436  void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
437  void get_poshold_attitude(float &roll_cd, float &pitch_cd, float &yaw_cd);
438 
439 #if LOGGING_ENABLED == ENABLED
440  void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
441  void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
442 #endif
443 
444  void send_step_string();
445  const char *level_issue_string() const;
446  const char * type_string() const;
447  void announce_state_to_gcs();
448  void do_gcs_announcements();
449 
450  enum LEVEL_ISSUE {
458  };
459  bool check_level(const enum LEVEL_ISSUE issue, const float current, const float maximum);
460  bool currently_level();
461 
462  // autotune modes (high level states)
463  enum TuneMode {
464  UNINITIALISED = 0, // autotune has never been run
465  TUNING = 1, // autotune is testing gains
466  SUCCESS = 2, // tuning has completed, user is flight testing the new gains
467  FAILED = 3, // tuning has failed, user is flying on original gains
468  };
469 
470  // steps performed while in the tuning mode
471  enum StepType {
472  WAITING_FOR_LEVEL = 0, // autotune is waiting for vehicle to return to level before beginning the next twitch
473  TWITCHING = 1, // autotune has begun a twitch and is watching the resulting vehicle movement
474  UPDATE_GAINS = 2 // autotune has completed a twitch and is updating the gains based on the results
475  };
476 
477  // things that can be tuned
478  enum AxisType {
479  ROLL = 0, // roll axis is being tuned (either angle or rate)
480  PITCH = 1, // pitch axis is being tuned (either angle or rate)
481  YAW = 2, // pitch axis is being tuned (either angle or rate)
482  };
483 
484  // mini steps performed while in Tuning mode, Testing step
485  enum TuneType {
486  RD_UP = 0, // rate D is being tuned up
487  RD_DOWN = 1, // rate D is being tuned down
488  RP_UP = 2, // rate P is being tuned up
489  SP_DOWN = 3, // angle P is being tuned down
490  SP_UP = 4 // angle P is being tuned up
491  };
492 
493  TuneMode mode : 2; // see TuneMode for what modes are allowed
494  bool pilot_override : 1; // true = pilot is overriding controls so we suspend tuning temporarily
495  AxisType axis : 2; // see AxisType for which things can be tuned
496  bool positive_direction : 1; // false = tuning in negative direction (i.e. left for roll), true = positive direction (i.e. right for roll)
497  StepType step : 2; // see StepType for what steps are performed
498  TuneType tune_type : 3; // see TuneType
499  bool ignore_next : 1; // true = ignore the next test
500  bool twitch_first_iter : 1; // true on first iteration of a twitch (used to signal we must step the attitude or rate target)
501  bool use_poshold : 1; // true = enable position hold
502  bool have_position : 1; // true = start_position is value
504 
505 // variables
506  uint32_t override_time; // the last time the pilot overrode the controls
507  float test_rate_min; // the minimum angular rate achieved during TESTING_RATE step
508  float test_rate_max; // the maximum angular rate achieved during TESTING_RATE step
509  float test_angle_min; // the minimum angle achieved during TESTING_ANGLE step
510  float test_angle_max; // the maximum angle achieved during TESTING_ANGLE step
511  uint32_t step_start_time; // start time of current tuning step (used for timeout checks)
512  uint32_t step_stop_time; // start time of current tuning step (used for timeout checks)
513  int8_t counter; // counter for tuning gains
514  float target_rate, start_rate; // target and start rate
515  float target_angle, start_angle; // target and start angles
516  float desired_yaw; // yaw heading during tune
517  float rate_max, test_accel_max; // maximum acceleration variables
518 
519  LowPassFilterFloat rotation_rate_filt; // filtered rotation rate in radians/second
520 
521 // backup of currently being tuned parameter values
522  float orig_roll_rp = 0, orig_roll_ri, orig_roll_rd, orig_roll_sp, orig_roll_accel;
523  float orig_pitch_rp = 0, orig_pitch_ri, orig_pitch_rd, orig_pitch_sp, orig_pitch_accel;
524  float orig_yaw_rp = 0, orig_yaw_ri, orig_yaw_rd, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel;
526 
527 // currently being tuned parameter values
528  float tune_roll_rp, tune_roll_rd, tune_roll_sp, tune_roll_accel;
529  float tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, tune_pitch_accel;
530  float tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, tune_yaw_accel;
531 
532  uint32_t announce_time;
533  float lean_angle;
536 
537  struct {
538  LEVEL_ISSUE issue{LEVEL_ISSUE_NONE};
539  float maximum;
540  float current;
541  } level_problem;
542 
543 };
544 #endif
545 
546 
547 class ModeBrake : public Mode {
548 
549 public:
550  // inherit constructor
551  using Copter::Mode::Mode;
552 
553  bool init(bool ignore_checks) override;
554  void run() override;
555 
556  bool requires_GPS() const override { return true; }
557  bool has_manual_throttle() const override { return false; }
558  bool allows_arming(bool from_gcs) const override { return false; };
559  bool is_autopilot() const override { return false; }
560 
561  void timeout_to_loiter_ms(uint32_t timeout_ms);
562 
563 protected:
564 
565  const char *name() const override { return "BRAKE"; }
566  const char *name4() const override { return "BRAK"; }
567 
568 private:
569 
570  uint32_t _timeout_start;
571  uint32_t _timeout_ms;
572 
573 };
574 
575 
576 class ModeCircle : public Mode {
577 
578 public:
579  // inherit constructor
580  using Copter::Mode::Mode;
581 
582  bool init(bool ignore_checks) override;
583  void run() override;
584 
585  bool requires_GPS() const override { return true; }
586  bool has_manual_throttle() const override { return false; }
587  bool allows_arming(bool from_gcs) const override { return false; };
588  bool is_autopilot() const override { return true; }
589 
590 protected:
591 
592  const char *name() const override { return "CIRCLE"; }
593  const char *name4() const override { return "CIRC"; }
594 
595  uint32_t wp_distance() const override;
596  int32_t wp_bearing() const override;
597 
598 private:
599 
600  // Circle
601  bool pilot_yaw_override = false; // true if pilot is overriding yaw
602 };
603 
604 
605 class ModeDrift : public Mode {
606 
607 public:
608  // inherit constructor
609  using Copter::Mode::Mode;
610 
611  bool init(bool ignore_checks) override;
612  void run() override;
613 
614  bool requires_GPS() const override { return true; }
615  bool has_manual_throttle() const override { return false; }
616  bool allows_arming(bool from_gcs) const override { return true; };
617  bool is_autopilot() const override { return false; }
618 
619 protected:
620 
621  const char *name() const override { return "DRIFT"; }
622  const char *name4() const override { return "DRIF"; }
623 
624 private:
625 
626  float get_throttle_assist(float velz, float pilot_throttle_scaled);
627 
628 };
629 
630 
631 class ModeFlip : public Mode {
632 
633 public:
634  // inherit constructor
635  using Copter::Mode::Mode;
636 
637  bool init(bool ignore_checks) override;
638  void run() override;
639 
640  bool requires_GPS() const override { return false; }
641  bool has_manual_throttle() const override { return false; }
642  bool allows_arming(bool from_gcs) const override { return false; };
643  bool is_autopilot() const override { return false; }
644 
645 protected:
646 
647  const char *name() const override { return "FLIP"; }
648  const char *name4() const override { return "FLIP"; }
649 
650 private:
651 
652  // Flip
653  Vector3f flip_orig_attitude; // original vehicle attitude before flip
654 
655 };
656 
657 
658 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
659 /*
660  class to support FLOWHOLD mode, which is a position hold mode using
661  optical flow directly, avoiding the need for a rangefinder
662  */
663 
664 class ModeFlowHold : public Mode {
665 public:
666  // need a constructor for parameters
667  ModeFlowHold(void);
668 
669  bool init(bool ignore_checks) override;
670  void run(void) override;
671 
672  bool requires_GPS() const override { return false; }
673  bool has_manual_throttle() const override { return false; }
674  bool allows_arming(bool from_gcs) const override { return true; };
675  bool is_autopilot() const override { return false; }
676 
677  static const struct AP_Param::GroupInfo var_info[];
678 
679 protected:
680  const char *name() const override { return "FLOWHOLD"; }
681  const char *name4() const override { return "FHLD"; }
682 
683 private:
684 
685  // FlowHold states
690  FlowHold_Landed
691  };
692 
693  // calculate attitude from flow data
694  void flow_to_angle(Vector2f &bf_angle);
695 
697 
698  bool flowhold_init(bool ignore_checks);
699  void flowhold_run();
700  void flowhold_flow_to_angle(Vector2f &angle, bool stick_input);
701  void update_height_estimate(void);
702 
703  // minimum assumed height
704  const float height_min = 0.1;
705 
706  // maximum scaling height
707  const float height_max = 3.0;
708 
709  AP_Float flow_max;
710  AC_PI_2D flow_pi_xy{0.2, 0.3, 3000, 5, 0.0025};
711  AP_Float flow_filter_hz;
713  AP_Int8 brake_rate_dps;
714 
716 
717  uint8_t log_counter;
718  bool limited;
720 
721  // accumulated INS delta velocity in north-east form since last flow update
723 
724  // last flow rate in radians/sec in north-east axis
726 
727  // timestamp of last flow data
728  uint32_t last_flow_ms;
729 
732 
733  // are we braking after pilot input?
734  bool braking;
735 
736  // last time there was significant stick input
738 };
739 #endif // OPTFLOW
740 
741 
742 class ModeGuided : public Mode {
743 
744 public:
745  // inherit constructor
746  using Copter::Mode::Mode;
747 
748  bool init(bool ignore_checks) override;
749  void run() override;
750 
751  bool requires_GPS() const override { return true; }
752  bool has_manual_throttle() const override { return false; }
753  bool allows_arming(bool from_gcs) const override { return from_gcs; }
754  bool is_autopilot() const override { return true; }
755  bool in_guided_mode() const { return true; }
756 
757  void set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads);
758  bool set_destination(const Vector3f& destination, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false);
759  bool set_destination(const Location_Class& dest_loc, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false);
760  bool get_wp(Location_Class &loc) override;
761  void set_velocity(const Vector3f& velocity, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false, bool log_request = true);
762  bool set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false);
763 
764  void limit_clear();
765  void limit_init_time_and_pos();
766  void limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm);
767  bool limit_check();
768 
769  bool takeoff_start(float final_alt_above_home);
770 
771  GuidedMode mode() const { return guided_mode; }
772 
773  void angle_control_start();
774  void angle_control_run();
775 
776 protected:
777 
778  const char *name() const override { return "GUIDED"; }
779  const char *name4() const override { return "GUID"; }
780 
781  uint32_t wp_distance() const override;
782  int32_t wp_bearing() const override;
783 
784 private:
785 
786  void pos_control_start();
787  void vel_control_start();
788  void posvel_control_start();
789  void takeoff_run();
790  void pos_control_run();
791  void vel_control_run();
792  void posvel_control_run();
793  void set_desired_velocity_with_accel_and_fence_limits(const Vector3f& vel_des);
794  void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle);
795 
796  // controls which controller is run (pos or vel):
797  GuidedMode guided_mode = Guided_TakeOff;
798 
799 };
800 
801 
802 class ModeGuidedNoGPS : public ModeGuided {
803 
804 public:
805  // inherit constructor
807 
808  bool init(bool ignore_checks) override;
809  void run() override;
810 
811  bool requires_GPS() const override { return true; }
812  bool has_manual_throttle() const override { return false; }
813  bool allows_arming(bool from_gcs) const override { return from_gcs; }
814  bool is_autopilot() const override { return true; }
815 
816 protected:
817 
818  const char *name() const override { return "GUIDED_NOGPS"; }
819  const char *name4() const override { return "GNGP"; }
820 
821 private:
822 
823 };
824 
825 
826 class ModeLand : public Mode {
827 
828 public:
829  // inherit constructor
830  using Copter::Mode::Mode;
831 
832  bool init(bool ignore_checks) override;
833  void run() override;
834 
835  bool requires_GPS() const override { return false; }
836  bool has_manual_throttle() const override { return false; }
837  bool allows_arming(bool from_gcs) const override { return false; };
838  bool is_autopilot() const override { return true; }
839  bool landing_gear_should_be_deployed() const override { return true; };
840 
841  void do_not_use_GPS();
842 
843 protected:
844 
845  const char *name() const override { return "LAND"; }
846  const char *name4() const override { return "LAND"; }
847 
848 private:
849 
850  void gps_run();
851  void nogps_run();
852 };
853 
854 
855 class ModeLoiter : public Mode {
856 
857 public:
858  // inherit constructor
859  using Copter::Mode::Mode;
860 
861  bool init(bool ignore_checks) override;
862  void run() override;
863 
864  bool requires_GPS() const override { return true; }
865  bool has_manual_throttle() const override { return false; }
866  bool allows_arming(bool from_gcs) const override { return true; };
867  bool is_autopilot() const override { return false; }
868 
869 #if PRECISION_LANDING == ENABLED
870  void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; }
871 #endif
872 
873 protected:
874 
875  const char *name() const override { return "LOITER"; }
876  const char *name4() const override { return "LOIT"; }
877 
878  uint32_t wp_distance() const override;
879  int32_t wp_bearing() const override;
880 
881 #if PRECISION_LANDING == ENABLED
882  bool do_precision_loiter();
883  void precision_loiter_xy();
884 #endif
885 
886 private:
887 
888 #if PRECISION_LANDING == ENABLED
890 #endif
891 
892 };
893 
894 
895 class ModePosHold : public Mode {
896 
897 public:
898  // inherit constructor
899  using Copter::Mode::Mode;
900 
901  bool init(bool ignore_checks) override;
902  void run() override;
903 
904  bool requires_GPS() const override { return true; }
905  bool has_manual_throttle() const override { return false; }
906  bool allows_arming(bool from_gcs) const override { return true; };
907  bool is_autopilot() const override { return false; }
908 
909 protected:
910 
911  const char *name() const override { return "POSHOLD"; }
912  const char *name4() const override { return "PHLD"; }
913 
914 private:
915 
916  void poshold_update_pilot_lean_angle(float &lean_angle_filtered, float &lean_angle_raw);
917  int16_t poshold_mix_controls(float mix_ratio, int16_t first_control, int16_t second_control);
918  void poshold_update_brake_angle_from_velocity(int16_t &brake_angle, float velocity);
919  void poshold_update_wind_comp_estimate();
920  void poshold_get_wind_comp_lean_angles(int16_t &roll_angle, int16_t &pitch_angle);
921  void poshold_roll_controller_to_pilot_override();
922  void poshold_pitch_controller_to_pilot_override();
923 
924 };
925 
926 
927 class ModeRTL : public Mode {
928 
929 public:
930  // inherit constructor
931  using Copter::Mode::Mode;
932 
933  bool init(bool ignore_checks) override;
934  void run() override {
935  return run(true);
936  }
937  void run(bool disarm_on_land);
938 
939  bool requires_GPS() const override { return true; }
940  bool has_manual_throttle() const override { return false; }
941  bool allows_arming(bool from_gcs) const override { return false; };
942  bool is_autopilot() const override { return true; }
943 
944  RTLState state() { return _state; }
945 
946  // this should probably not be exposed
947  bool state_complete() { return _state_complete; }
948 
949  bool landing_gear_should_be_deployed() const override;
950 
951  void restart_without_terrain();
952 
953 protected:
954 
955  const char *name() const override { return "RTL"; }
956  const char *name4() const override { return "RTL "; }
957 
958  uint32_t wp_distance() const override;
959  int32_t wp_bearing() const override;
960 
961  void descent_start();
962  void descent_run();
963  void land_start();
964  void land_run(bool disarm_on_land);
965 
966  void set_descent_target_alt(uint32_t alt) { rtl_path.descent_target.alt = alt; }
967 
968 private:
969 
970  void climb_start();
971  void return_start();
972  void climb_return_run();
973  void loiterathome_start();
974  void loiterathome_run();
975  void build_path(bool terrain_following_allowed);
976  void compute_return_target(bool terrain_following_allowed);
977 
978  // RTL
979  RTLState _state = RTL_InitialClimb; // records state of rtl (initial climb, returning home, etc)
980  bool _state_complete = false; // set to true if the current state is completed
981 
982  struct {
983  // NEU w/ Z element alt-above-ekf-origin unless use_terrain is true in which case Z element is alt-above-terrain
988  bool land;
990  } rtl_path;
991 
992  // Loiter timer - Records how long we have been in loiter
993  uint32_t _loiter_start_time = 0;
994 };
995 
996 
997 class ModeSmartRTL : public ModeRTL {
998 
999 public:
1000  // inherit constructor
1001  using Copter::ModeRTL::Mode;
1002 
1003  bool init(bool ignore_checks) override;
1004  void run() override;
1005 
1006  bool requires_GPS() const override { return true; }
1007  bool has_manual_throttle() const override { return false; }
1008  bool allows_arming(bool from_gcs) const override { return false; }
1009  bool is_autopilot() const override { return true; }
1010 
1011  void save_position();
1012  void exit();
1013 
1014 protected:
1015 
1016  const char *name() const override { return "SMARTRTL"; }
1017  const char *name4() const override { return "SRTL"; }
1018 
1019  uint32_t wp_distance() const override;
1020  int32_t wp_bearing() const override;
1021 
1022 private:
1023 
1024  void wait_cleanup_run();
1025  void path_follow_run();
1026  void pre_land_position_run();
1027  void land();
1029 
1030 };
1031 
1032 
1033 class ModeSport : public Mode {
1034 
1035 public:
1036  // inherit constructor
1037  using Copter::Mode::Mode;
1038 
1039  bool init(bool ignore_checks) override;
1040  void run() override;
1041 
1042  bool requires_GPS() const override { return false; }
1043  bool has_manual_throttle() const override { return false; }
1044  bool allows_arming(bool from_gcs) const override { return true; };
1045  bool is_autopilot() const override { return false; }
1046 
1047 protected:
1048 
1049  const char *name() const override { return "SPORT"; }
1050  const char *name4() const override { return "SPRT"; }
1051 
1052 private:
1053 
1054 };
1055 
1056 
1057 class ModeStabilize : public Mode {
1058 
1059 public:
1060  // inherit constructor
1061  using Copter::Mode::Mode;
1062 
1063  virtual bool init(bool ignore_checks) override;
1064  virtual void run() override;
1065 
1066  bool requires_GPS() const override { return false; }
1067  bool has_manual_throttle() const override { return true; }
1068  bool allows_arming(bool from_gcs) const override { return true; };
1069  bool is_autopilot() const override { return false; }
1070 
1071 protected:
1072 
1073  const char *name() const override { return "STABILIZE"; }
1074  const char *name4() const override { return "STAB"; }
1075 
1076 private:
1077 
1078 };
1079 
1080 #if FRAME_CONFIG == HELI_FRAME
1082 
1083 public:
1084  // inherit constructor
1086 
1087  bool init(bool ignore_checks) override;
1088  void run() override;
1089 
1090 protected:
1091 
1092 private:
1093 
1094 };
1095 #endif
1096 
1097 
1098 class ModeThrow : public Mode {
1099 
1100 public:
1101  // inherit constructor
1102  using Copter::Mode::Mode;
1103 
1104  bool init(bool ignore_checks) override;
1105  void run() override;
1106 
1107  bool requires_GPS() const override { return true; }
1108  bool has_manual_throttle() const override { return false; }
1109  bool allows_arming(bool from_gcs) const override { return true; };
1110  bool is_autopilot() const override { return false; }
1111 
1112  // Throw types
1114  ThrowType_Upward = 0,
1115  ThrowType_Drop = 1
1116  };
1117 
1118 protected:
1119 
1120  const char *name() const override { return "THROW"; }
1121  const char *name4() const override { return "THRW"; }
1122 
1123 private:
1124 
1125  bool throw_detected();
1126  bool throw_position_good();
1127  bool throw_height_good();
1128  bool throw_attitude_good();
1129 
1130  // Throw stages
1136  Throw_PosHold
1137  };
1138 
1139  ThrowModeStage stage = Throw_Disarmed;
1140  ThrowModeStage prev_stage = Throw_Disarmed;
1141  uint32_t last_log_ms;
1143  uint32_t free_fall_start_ms; // system time free fall was detected
1144  float free_fall_start_velz; // vertical velocity when free fall was detected
1145 };
1146 
1147 // modes below rely on Guided mode so must be declared at the end (instead of in alphabetical order)
1148 
1149 class ModeAvoidADSB : public ModeGuided {
1150 
1151 public:
1152  // inherit constructor
1154 
1155  bool init(bool ignore_checks) override;
1156  void run() override;
1157 
1158  bool requires_GPS() const override { return true; }
1159  bool has_manual_throttle() const override { return false; }
1160  bool allows_arming(bool from_gcs) const override { return false; }
1161  bool is_autopilot() const override { return true; }
1162 
1163  bool set_velocity(const Vector3f& velocity_neu);
1164 
1165 protected:
1166 
1167  const char *name() const override { return "AVOID_ADSB"; }
1168  const char *name4() const override { return "AVOI"; }
1169 
1170 private:
1171 
1172 };
1173 
1174 class ModeFollow : public ModeGuided {
1175 
1176 public:
1177 
1178  // inherit constructor
1180 
1181  bool init(bool ignore_checks) override;
1182  void run() override;
1183 
1184  bool requires_GPS() const override { return true; }
1185  bool has_manual_throttle() const override { return false; }
1186  bool allows_arming(bool from_gcs) const override { return false; }
1187  bool is_autopilot() const override { return true; }
1188 
1189 protected:
1190 
1191  const char *name() const override { return "FOLLOW"; }
1192  const char *name4() const override { return "FOLL"; }
1193 
1194  uint32_t last_log_ms; // system time of last time desired velocity was logging
1195 };
const char * name4() const override
Definition: mode.h:622
bool is_autopilot() const override
Definition: mode.h:588
float descend_max
Definition: mode.h:386
void land_run_vertical_control(bool pause_descent=false)
bool requires_GPS() const override
Definition: mode.h:1006
const char * name() const override
Definition: mode.h:647
AC_PosControl *& pos_control
Definition: mode.h:119
bool has_manual_throttle() const override
Definition: mode.h:836
ThrowModeType
Definition: mode.h:1113
Vector2f delta_velocity_ne
Definition: mode.h:722
bool has_manual_throttle() const override
Definition: mode.h:1108
float lean_angle
Definition: mode.h:533
RC_Channel *& channel_throttle
Definition: mode.h:126
float tune_roll_sp
Definition: mode.h:528
Location_Class origin_point
Definition: mode.h:984
bool orig_bf_feedforward
Definition: mode.h:525
bool requires_GPS() const override
Definition: mode.h:751
bool has_manual_throttle() const override
Definition: mode.h:557
bool allows_arming(bool from_gcs) const override
Definition: mode.h:616
bool is_autopilot() const override
Definition: mode.h:404
const char * name() const override
Definition: mode.h:845
bool allows_arming(bool from_gcs) const override
Definition: mode.h:753
bool has_manual_throttle() const override
Definition: mode.h:940
const char * name() const override
Definition: mode.h:1016
uint32_t last_flow_ms
Definition: mode.h:728
Vector2f xy_I
Definition: mode.h:719
LowPassFilterFloat rotation_rate_filt
Definition: mode.h:519
const char * name() const override
Definition: mode.h:592
float test_rate_max
Definition: mode.h:508
const char * name4() const override
Definition: mode.h:593
bool allows_arming(bool from_gcs) const override
Definition: mode.h:813
const char * name() const override
Definition: mode.h:911
control_mode_t
Definition: defines.h:91
bool is_autopilot() const override
Definition: mode.h:1069
float _look_ahead_yaw
Definition: mode.h:63
bool is_autopilot() const override
Definition: mode.h:176
StepType step
Definition: mode.h:497
bool limited
Definition: mode.h:718
uint8_t _mode
Definition: mode.h:48
spline_segment_end_type
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
float tune_yaw_sp
Definition: mode.h:530
float test_angle_min
Definition: mode.h:509
const char * name() const override
Definition: mode.h:1167
virtual bool in_guided_mode() const
Definition: mode.h:97
autopilot_yaw_mode mode() const
Definition: mode.h:25
Vector3f start_position
Definition: mode.h:503
bool is_autopilot() const override
Definition: mode.h:1110
float _roi_yaw
Definition: mode.h:54
const char * name() const override
Definition: mode.h:818
Definition: mode.h:826
Definition: mode.h:631
bool allows_arming(bool from_gcs) const override
Definition: mode.h:866
const char * name4() const override
Definition: mode.h:1074
float & ekfNavVelGainScaler
Definition: mode.h:136
bool terrain_used
Definition: mode.h:989
void zero_throttle_and_relax_ac()
AxisType axis
Definition: mode.h:495
float & ekfGndSpdLimit
Definition: mode.h:133
bool takeoff_triggered(float target_climb_rate) const
RTLState
Definition: defines.h:217
uint16_t get_pilot_speed_dn(void)
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
const char * name() const override
Definition: mode.h:278
Definition: mode.h:5
Vector2f last_flow_rate_rps
Definition: mode.h:725
float descend_throttle_level
Definition: mode.h:384
void set_throttle_takeoff(void)
const AP_Param::Info var_info[]
int16_t _fixed_yaw_slewrate
Definition: mode.h:60
uint16_t loiter_time_max
Definition: mode.h:365
LandStateType
Definition: defines.h:268
bool is_autopilot() const override
Definition: mode.h:907
float quality_filtered
Definition: mode.h:715
float roll_cd
Definition: mode.h:535
Definition: Copter.h:180
float test_rate_min
Definition: mode.h:507
bool in_guided_mode() const
Definition: mode.h:755
uint32_t step_start_time
Definition: mode.h:511
uint32_t last_log_ms
Definition: mode.h:1194
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1160
const char * name() const override
Definition: mode.h:1120
RC_Channel *& channel_pitch
Definition: mode.h:125
virtual bool is_autopilot() const
Definition: mode.h:79
TuneMode mode
Definition: mode.h:493
bool use_yaw_rate
Definition: mode_guided.cpp:26
const char * name() const override
Definition: mode.h:225
bool requires_GPS() const override
Definition: mode.h:864
Mode(void)
Definition: mode.cpp:11
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1068
RTLState state()
Definition: mode.h:944
const char * name() const override
Definition: mode.h:621
Vector3f roi
Definition: mode.h:51
#define MOTOR_CLASS
Definition: Copter.h:419
uint32_t descend_start_timestamp
Definition: mode.h:382
const char * name() const override
Definition: mode.h:1191
uint32_t condition_start
Definition: mode.h:374
Vector3f flip_orig_attitude
Definition: mode.h:653
const char * name4() const override
Definition: mode.h:846
AP_Float flow_max
Definition: mode.h:709
bool is_autopilot() const override
Definition: mode.h:1009
bool land
Definition: mode.h:988
const char * name4() const override
Definition: mode.h:648
float pitch_cd
Definition: mode_guided.cpp:22
Location_Class return_target
Definition: mode.h:986
bool has_manual_throttle() const override
Definition: mode.h:1043
float look_ahead_yaw()
void takeoff_timer_start(float alt_cm)
bool requires_GPS() const override
Definition: mode.h:1107
bool use_poshold
Definition: mode.h:501
mode_reason_t
Definition: defines.h:115
bool pilot_override
Definition: mode.h:494
bool allows_arming(bool from_gcs) const override
Definition: mode.h:403
const char * name4() const override
Definition: mode.h:1121
virtual int32_t wp_bearing() const
Definition: mode.h:95
Location_Class descent_target
Definition: mode.h:987
bool is_autopilot() const override
Definition: mode.h:559
float descend_start_altitude
Definition: mode.h:385
bool has_manual_throttle() const override
Definition: mode.h:812
int32_t nav_delay_time_max
Definition: mode.h:369
Parameters & g
Definition: mode.h:115
float orig_roll_sp
Definition: mode.h:522
void set_precision_loiter_enabled(bool value)
Definition: mode.h:870
uint32_t hover_start_timestamp
Definition: mode.h:380
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1186
const char * name4() const override
Definition: mode.h:956
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1109
void run() override
Definition: mode.h:934
uint8_t roi_yaw_counter
Definition: mode.h:69
const char * name4() const override
Definition: mode.h:779
float rate_cds() const
bool requires_GPS() const override
Definition: mode.h:672
const char * name() const override
Definition: mode.h:1049
bool is_autopilot() const override
Definition: mode.h:867
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1044
uint32_t loiter_time
Definition: mode.h:366
uint32_t free_fall_start_ms
Definition: mode.h:1143
bool has_manual_throttle() const override
Definition: mode.h:244
void set_mode_to_default(bool rtl)
const char * name() const override
Definition: mode.h:1073
bool allows_arming(bool from_gcs) const override
Definition: mode.h:179
const char * name4() const override
Definition: mode.h:566
bool positive_direction
Definition: mode.h:496
virtual void run()=0
bool has_manual_throttle() const override
Definition: mode.h:1185
Definition: mode.h:927
Mode(void)
AP_InertialNav & inertial_nav
Definition: mode.h:120
const char * name4() const override
Definition: mode.h:681
AutoMode mode() const
Definition: mode.h:249
bool allows_arming(bool from_gcs) const override
Definition: mode.h:906
bool has_manual_throttle() const override
Definition: mode.h:615
float test_angle_max
Definition: mode.h:510
bool allows_arming(bool from_gcs) const override
Definition: mode.h:837
bool allows_arming(bool from_gcs) const override
Definition: mode.h:587
virtual const char * name4() const =0
bool has_manual_throttle() const override
Definition: mode.h:905
bool is_autopilot() const override
Definition: mode.h:242
virtual bool landing_gear_should_be_deployed() const
Definition: mode.h:84
uint32_t last_stick_input_ms
Definition: mode.h:737
bool requires_GPS() const override
Definition: mode.h:640
bool has_manual_throttle() const override
Definition: mode.h:1007
bool is_autopilot() const override
Definition: mode.h:942
float maximum
Definition: mode.h:539
float hover_throttle_level
Definition: mode.h:381
uint32_t _timeout_start
Definition: mode.h:570
#define AC_AttitudeControl_t
Definition: Copter.h:490
AC_WPNav *& wp_nav
Definition: mode.h:117
AP_Float flow_filter_hz
Definition: mode.h:711
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
bool requires_GPS() const override
Definition: mode.h:1158
bool ignore_next
Definition: mode.h:499
bool has_manual_throttle() const override
Definition: mode.h:1067
bool has_manual_throttle() const override
Definition: mode.h:178
float test_accel_max
Definition: mode.h:517
int8_t counter
Definition: mode.h:513
const char * name() const override
Definition: mode.h:680
bool is_autopilot() const override
Definition: mode.h:221
bool has_manual_throttle() const override
Definition: mode.h:865
bool requires_GPS() const override
Definition: mode.h:1066
bool has_manual_throttle() const override
Definition: mode.h:1159
static AutoYaw auto_yaw
Definition: mode.h:72
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
ParametersG2 & g2
Definition: mode.h:116
float get_non_takeoff_throttle(void)
const char * name() const override
Definition: mode.h:875
bool requires_GPS() const override
Definition: mode.h:556
uint32_t step_stop_time
Definition: mode.h:512
AutoMode
Definition: defines.h:194
TuneType tune_type
Definition: mode.h:498
float orig_yaw_sp
Definition: mode.h:524
virtual bool init(bool ignore_checks)=0
bool has_manual_throttle() const override
Definition: mode.h:586
bool requires_GPS() const override
Definition: mode.h:811
virtual const char * name() const =0
int32_t get_alt_above_ground(void)
const char * name4() const override
Definition: mode.h:819
void update_simple_mode(void)
AP_Int8 brake_rate_dps
Definition: mode.h:713
float & G_Dt
Definition: mode.h:128
float _rate_cds
Definition: mode.h:66
float roll_cd
Definition: mode_guided.cpp:21
PayloadPlaceStateType
Definition: defines.h:273
bool allows_arming(bool from_gcs) const override
Definition: mode.h:941
bool have_position
Definition: mode.h:502
uint32_t last_log_ms
Definition: mode.h:1141
Definition: mode.h:233
bool requires_GPS() const override
Definition: mode.h:218
bool in_guided_mode() const
Definition: mode.h:246
AP_AHRS & ahrs
Definition: mode.h:121
virtual bool requires_GPS() const =0
const char * name4() const override
Definition: mode.h:1050
bool nextmode_attempted
Definition: mode.h:1142
uint32_t announce_time
Definition: mode.h:532
bool landing_gear_should_be_deployed() const override
Definition: mode.h:839
float get_avoidance_adjusted_climbrate(float target_rate)
void set_descent_target_alt(uint32_t alt)
Definition: mode.h:966
GuidedMode
Definition: defines.h:208
bool allows_arming(bool from_gcs) const override
Definition: mode.h:220
const char * name() const override
Definition: mode.h:412
bool requires_GPS() const override
Definition: mode.h:1042
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
GuidedMode mode() const
Definition: mode.h:771
Definition: mode.h:167
const char * name4() const override
Definition: mode.h:1017
float climb_rate_cms
Definition: mode_guided.cpp:25
int32_t _fixed_yaw
Definition: mode.h:57
bool has_manual_throttle() const override
Definition: mode.h:673
uint32_t override_time
Definition: mode.h:506
Location_Class climb_target
Definition: mode.h:985
float desired_yaw
Definition: mode.h:516
uint32_t nav_delay_time_start
Definition: mode.h:370
void land_run_horizontal_control()
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1008
RC_Channel *& channel_roll
Definition: mode.h:124
heli_flags_t & heli_flags
Definition: mode.h:139
bool allows_arming(bool from_gcs) const override
Definition: mode.h:642
bool has_manual_throttle() const override
Definition: mode.h:752
float free_fall_start_velz
Definition: mode.h:1144
uint8_t log_counter
Definition: mode.h:717
bool braking
Definition: mode.h:734
autopilot_yaw_mode default_mode(bool rtl) const
void update_navigation()
bool is_autopilot() const override
Definition: mode.h:1045
float get_pilot_desired_yaw_rate(int16_t stick_angle)
virtual bool allows_arming(bool from_gcs) const =0
RC_Channel *& channel_yaw
Definition: mode.h:127
void set_roi(const Location &roi_location)
bool is_autopilot() const override
Definition: mode.h:838
const char * name4() const override
Definition: mode.h:876
takeoff_state_t & takeoff_state
Definition: mode.h:130
float yaw_cd
Definition: mode_guided.cpp:23
FlowHoldModeState
Definition: mode.h:686
bool _precision_loiter_enabled
Definition: mode.h:889
bool requires_GPS() const override
Definition: mode.h:904
virtual bool get_wp(Location_Class &loc)
Definition: mode.h:96
autopilot_yaw_mode
Definition: defines.h:14
bool requires_GPS() const override
Definition: mode.h:939
AC_Loiter *& loiter_nav
Definition: mode.h:118
AP_Int8 flow_min_quality
Definition: mode.h:712
void takeoff_stop(void)
float target_angle
Definition: mode.h:515
AC_AttitudeControl_t *& attitude_control
Definition: mode.h:122
const char * name4() const override
Definition: mode.h:184
void set_land_complete(bool b)
float rotation_rate
Definition: mode.h:534
bool allows_arming(bool from_gcs) const override
Definition: mode.h:674
bool requires_GPS() const override
Definition: mode.h:835
float roi_yaw()
bool requires_GPS() const override
Definition: mode.h:177
bool requires_GPS() const override
Definition: mode.h:1184
bool is_autopilot() const override
Definition: mode.h:1161
bool has_manual_throttle() const override
Definition: mode.h:641
bool has_manual_throttle() const override
Definition: mode.h:402
bool allows_arming(bool from_gcs) const override
Definition: mode.h:245
const char * name4() const override
Definition: mode.h:413
virtual bool has_manual_throttle() const =0
int32_t condition_value
Definition: mode.h:373
bool requires_GPS() const override
Definition: mode.h:243
bool has_manual_throttle() const override
Definition: mode.h:219
float tune_pitch_sp
Definition: mode.h:529
bool requires_GPS() const override
Definition: mode.h:585
LowPassFilterVector2f flow_filter
Definition: mode.h:696
bool is_autopilot() const override
Definition: mode.h:617
uint32_t _timeout_ms
Definition: mode.h:571
bool is_autopilot() const override
Definition: mode.h:643
bool is_autopilot() const override
Definition: mode.h:675
const char * name() const override
Definition: mode.h:565
virtual void run_autopilot()
Definition: mode.h:93
bool is_autopilot() const override
Definition: mode.h:814
ap_t & ap
Definition: mode.h:129
ThrowModeStage
Definition: mode.h:1131
void set_fixed_yaw(float angle_deg, float turn_rate_dps, int8_t direction, bool relative_angle)
bool twitch_first_iter
Definition: mode.h:500
virtual uint32_t wp_distance() const
Definition: mode.h:94
uint32_t place_start_timestamp
Definition: mode.h:383
const char * name4() const override
Definition: mode.h:1168
float target_rate
Definition: mode.h:514
const char * name() const override
Definition: mode.h:183
void set_rate(float new_rate_cds)
const char * name4() const override
Definition: mode.h:912
MOTOR_CLASS *& motors
Definition: mode.h:123
bool state_complete()
Definition: mode.h:947
float height_offset
Definition: mode.h:731
const char * name4() const override
Definition: mode.h:226
float yaw_rate_cds
Definition: mode_guided.cpp:24
GCS_Copter & gcs()
bool is_autopilot() const override
Definition: mode.h:1187
SmartRTLState
Definition: defines.h:226
bool requires_GPS() const override
Definition: mode.h:614
bool requires_GPS() const override
Definition: mode.h:401
const char * name() const override
Definition: mode.h:778
float current
Definition: mode.h:540
void set_mode(autopilot_yaw_mode new_mode)
bool allows_arming(bool from_gcs) const override
Definition: mode.h:558
void Log_Write_Event(uint8_t id)
float last_ins_height
Definition: mode.h:730
const char * name4() const override
Definition: mode.h:1192
bool is_autopilot() const override
Definition: mode.h:754
float orig_pitch_sp
Definition: mode.h:523
const char * name4() const override
Definition: mode.h:279
const char * name() const override
Definition: mode.h:955
float get_pilot_desired_climb_rate(float throttle_control)