35 void set_roi(
const Location &roi_location);
44 float look_ahead_yaw();
60 int16_t _fixed_yaw_slewrate;
63 float _look_ahead_yaw;
69 uint8_t roi_yaw_counter;
76 virtual bool init(
bool ignore_checks) = 0;
77 virtual void run() = 0;
86 virtual const char *
name()
const = 0;
89 virtual const char *
name4()
const = 0;
96 virtual bool get_wp(Location_Class &loc) {
return false; };
138 #if FRAME_CONFIG == HELI_FRAME 166 #if MODE_ACRO_ENABLED == ENABLED 171 using Copter::Mode::Mode;
173 virtual bool init(
bool ignore_checks)
override;
174 virtual void run()
override;
183 const char *
name()
const override {
return "ACRO"; }
184 const char *
name4()
const override {
return "ACRO"; }
193 #if FRAME_CONFIG == HELI_FRAME 198 using Copter::ModeAcro::Mode;
200 bool init(
bool ignore_checks)
override;
213 using Copter::Mode::Mode;
215 bool init(
bool ignore_checks)
override;
225 const char *
name()
const override {
return "ALT_HOLD"; }
226 const char *
name4()
const override {
return "ALTH"; }
237 using Copter::Mode::Mode;
239 bool init(
bool ignore_checks)
override;
254 void wp_start(
const Vector3f& destination);
255 void wp_start(
const Location_Class& dest_loc);
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);
274 bool do_guided(
const AP_Mission::Mission_Command& cmd);
278 const char *
name()
const override {
return "AUTO"; }
279 const char *
name4()
const override {
return "AUTO"; }
283 bool get_wp(Location_Class &loc)
override;
288 bool verify_command(
const AP_Mission::Mission_Command& cmd);
296 void nav_guided_run();
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();
308 Location_Class terrain_adjusted_location(
const AP_Mission::Mission_Command& cmd)
const;
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);
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);
333 #if PARACHUTE == ENABLED 334 void do_parachute(
const AP_Mission::Mission_Command& cmd);
336 #if GRIPPER_ENABLED == ENABLED 337 void do_gripper(
const AP_Mission::Mission_Command& cmd);
339 #if WINCH_ENABLED == ENABLED 340 void do_winch(
const AP_Mission::Mission_Command& cmd);
342 void do_payload_place(
const AP_Mission::Mission_Command& cmd);
345 bool verify_takeoff();
347 bool verify_payload_place();
348 bool verify_loiter_unlimited();
349 bool verify_loiter_time();
351 bool verify_wait_delay();
352 bool verify_within_distance();
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);
360 bool verify_nav_delay(
const AP_Mission::Mission_Command& cmd);
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);
365 uint16_t loiter_time_max;
366 uint32_t loiter_time;
369 int32_t nav_delay_time_max;
370 uint32_t nav_delay_time_start;
373 int32_t condition_value;
374 uint32_t condition_start;
391 #if AUTOTUNE_ENABLED == ENABLED 396 using Copter::Mode::Mode;
398 bool init(
bool ignore_checks)
override;
412 const char *
name()
const override {
return "AUTOTUNE"; }
413 const char *
name4()
const override {
return "ATUN"; }
417 bool start(
bool ignore_checks);
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);
427 bool pitch_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);
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);
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();
452 LEVEL_ISSUE_ANGLE_ROLL,
453 LEVEL_ISSUE_ANGLE_PITCH,
454 LEVEL_ISSUE_ANGLE_YAW,
455 LEVEL_ISSUE_RATE_ROLL,
456 LEVEL_ISSUE_RATE_PITCH,
457 LEVEL_ISSUE_RATE_YAW,
460 bool currently_level();
472 WAITING_FOR_LEVEL = 0,
494 bool pilot_override : 1;
496 bool positive_direction : 1;
498 TuneType tune_type : 3;
499 bool ignore_next : 1;
500 bool twitch_first_iter : 1;
501 bool use_poshold : 1;
502 bool have_position : 1;
503 Vector3f start_position;
506 uint32_t override_time;
509 float test_angle_min;
510 float test_angle_max;
511 uint32_t step_start_time;
512 uint32_t step_stop_time;
514 float target_rate, start_rate;
515 float target_angle, start_angle;
517 float rate_max, test_accel_max;
519 LowPassFilterFloat rotation_rate_filt;
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;
525 bool orig_bf_feedforward;
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;
532 uint32_t announce_time;
535 float roll_cd, pitch_cd;
538 LEVEL_ISSUE
issue{LEVEL_ISSUE_NONE};
551 using Copter::Mode::Mode;
553 bool init(
bool ignore_checks)
override;
565 const char *
name()
const override {
return "BRAKE"; }
566 const char *
name4()
const override {
return "BRAK"; }
570 uint32_t _timeout_start;
571 uint32_t _timeout_ms;
580 using Copter::Mode::Mode;
582 bool init(
bool ignore_checks)
override;
592 const char *
name()
const override {
return "CIRCLE"; }
593 const char *
name4()
const override {
return "CIRC"; }
601 bool pilot_yaw_override =
false;
609 using Copter::Mode::Mode;
611 bool init(
bool ignore_checks)
override;
621 const char *
name()
const override {
return "DRIFT"; }
622 const char *
name4()
const override {
return "DRIF"; }
626 float get_throttle_assist(
float velz,
float pilot_throttle_scaled);
635 using Copter::Mode::Mode;
637 bool init(
bool ignore_checks)
override;
647 const char *
name()
const override {
return "FLIP"; }
648 const char *
name4()
const override {
return "FLIP"; }
653 Vector3f flip_orig_attitude;
658 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED 669 bool init(
bool ignore_checks)
override;
670 void run(
void)
override;
677 static const struct AP_Param::GroupInfo
var_info[];
680 const char *
name()
const override {
return "FLOWHOLD"; }
681 const char *
name4()
const override {
return "FHLD"; }
686 enum FlowHoldModeState {
687 FlowHold_MotorStopped,
694 void flow_to_angle(Vector2f &bf_angle);
696 LowPassFilterVector2f flow_filter;
698 bool flowhold_init(
bool ignore_checks);
700 void flowhold_flow_to_angle(Vector2f &angle,
bool stick_input);
701 void update_height_estimate(
void);
704 const float height_min = 0.1;
707 const float height_max = 3.0;
710 AC_PI_2D flow_pi_xy{0.2, 0.3, 3000, 5, 0.0025};
711 AP_Float flow_filter_hz;
712 AP_Int8 flow_min_quality;
713 AP_Int8 brake_rate_dps;
715 float quality_filtered;
722 Vector2f delta_velocity_ne;
725 Vector2f last_flow_rate_rps;
728 uint32_t last_flow_ms;
730 float last_ins_height;
737 uint32_t last_stick_input_ms;
746 using Copter::Mode::Mode;
748 bool init(
bool ignore_checks)
override;
760 bool get_wp(Location_Class &loc)
override;
766 void limit_set(uint32_t timeout_ms,
float alt_min_cm,
float alt_max_cm,
float horiz_max_cm);
778 const char *
name()
const override {
return "GUIDED"; }
779 const char *
name4()
const override {
return "GUID"; }
786 void pos_control_start();
787 void vel_control_start();
788 void posvel_control_start();
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);
806 using Copter::ModeGuided::Mode;
808 bool init(
bool ignore_checks)
override;
818 const char *
name()
const override {
return "GUIDED_NOGPS"; }
819 const char *
name4()
const override {
return "GNGP"; }
830 using Copter::Mode::Mode;
832 bool init(
bool ignore_checks)
override;
845 const char *
name()
const override {
return "LAND"; }
846 const char *
name4()
const override {
return "LAND"; }
859 using Copter::Mode::Mode;
861 bool init(
bool ignore_checks)
override;
869 #if PRECISION_LANDING == ENABLED 875 const char *
name()
const override {
return "LOITER"; }
876 const char *
name4()
const override {
return "LOIT"; }
881 #if PRECISION_LANDING == ENABLED 888 #if PRECISION_LANDING == ENABLED 889 bool _precision_loiter_enabled;
899 using Copter::Mode::Mode;
901 bool init(
bool ignore_checks)
override;
911 const char *
name()
const override {
return "POSHOLD"; }
912 const char *
name4()
const override {
return "PHLD"; }
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();
931 using Copter::Mode::Mode;
933 bool init(
bool ignore_checks)
override;
937 void run(
bool disarm_on_land);
955 const char *
name()
const override {
return "RTL"; }
956 const char *
name4()
const override {
return "RTL "; }
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);
980 bool _state_complete =
false;
993 uint32_t _loiter_start_time = 0;
1001 using Copter::ModeRTL::Mode;
1003 bool init(
bool ignore_checks)
override;
1004 void run()
override;
1016 const char *
name()
const override {
return "SMARTRTL"; }
1017 const char *
name4()
const override {
return "SRTL"; }
1024 void wait_cleanup_run();
1025 void path_follow_run();
1026 void pre_land_position_run();
1037 using Copter::Mode::Mode;
1039 bool init(
bool ignore_checks)
override;
1040 void run()
override;
1049 const char *
name()
const override {
return "SPORT"; }
1050 const char *
name4()
const override {
return "SPRT"; }
1061 using Copter::Mode::Mode;
1063 virtual bool init(
bool ignore_checks)
override;
1064 virtual void run()
override;
1073 const char *
name()
const override {
return "STABILIZE"; }
1074 const char *
name4()
const override {
return "STAB"; }
1080 #if FRAME_CONFIG == HELI_FRAME 1085 using Copter::ModeStabilize::Mode;
1087 bool init(
bool ignore_checks)
override;
1088 void run()
override;
1102 using Copter::Mode::Mode;
1104 bool init(
bool ignore_checks)
override;
1105 void run()
override;
1120 const char *
name()
const override {
return "THROW"; }
1121 const char *
name4()
const override {
return "THRW"; }
1125 bool throw_detected();
1126 bool throw_position_good();
1127 bool throw_height_good();
1128 bool throw_attitude_good();
1131 enum ThrowModeStage {
1139 ThrowModeStage stage = Throw_Disarmed;
1140 ThrowModeStage prev_stage = Throw_Disarmed;
1141 uint32_t last_log_ms;
1142 bool nextmode_attempted;
1143 uint32_t free_fall_start_ms;
1144 float free_fall_start_velz;
1153 using Copter::ModeGuided::Mode;
1155 bool init(
bool ignore_checks)
override;
1156 void run()
override;
1167 const char *
name()
const override {
return "AVOID_ADSB"; }
1168 const char *
name4()
const override {
return "AVOI"; }
1179 using Copter::ModeGuided::Mode;
1181 bool init(
bool ignore_checks)
override;
1182 void run()
override;
1191 const char *
name()
const override {
return "FOLLOW"; }
1192 const char *
name4()
const override {
return "FOLL"; }
virtual bool landing_gear_should_be_deployed() const
Definition: mode.h:84
bool is_autopilot() const override
Definition: mode.h:1161
bool init(bool ignore_checks) override
virtual bool init(bool ignore_checks)=0
bool init(bool ignore_checks) override
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1068
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)
Definition: defines.h:269
float get_pilot_desired_yaw_rate(int16_t stick_angle)
const char * name4() const override
Definition: mode.h:846
bool init(bool ignore_checks) override
RTLState state()
Definition: mode.h:944
bool in_guided_mode() const
Definition: mode.h:755
bool has_manual_throttle() const override
Definition: mode.h:641
void spline_start(const Vector3f &destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Vector3f &next_spline_destination)
bool is_autopilot() const override
Definition: mode.h:1187
void wp_start(const Vector3f &destination)
const char * name() const override
Definition: mode.h:1016
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1008
bool requires_GPS() const override
Definition: mode.h:556
const char * name() const override
Definition: mode.h:647
bool is_autopilot() const override
Definition: mode.h:942
bool has_manual_throttle() const override
Definition: mode.h:905
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1186
bool has_manual_throttle() const override
Definition: mode.h:1108
virtual bool allows_arming(bool from_gcs) const =0
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1044
const char * name4() const override
Definition: mode.h:1050
control_mode_t
Definition: defines.h:91
float & ekfGndSpdLimit
Definition: mode.h:133
bool is_autopilot() const override
Definition: mode.h:617
bool is_autopilot() const override
Definition: mode.h:675
float get_pilot_desired_climb_rate(float throttle_control)
Definition: GCS_Copter.h:6
#define AC_AttitudeControl_t
Definition: Copter.h:483
bool is_autopilot() const override
Definition: mode.h:838
RTLState
Definition: defines.h:217
bool get_wp(Location_Class &loc) override
AutoMode mode() const
Definition: mode.h:249
bool do_guided(const AP_Mission::Mission_Command &cmd)
uint32_t place_start_timestamp
Definition: mode.h:383
virtual bool get_wp(Location_Class &loc)
Definition: mode.h:96
Definition: defines.h:209
const char * name() const override
Definition: mode.h:1049
bool allows_arming(bool from_gcs) const override
Definition: mode.h:616
void timeout_to_loiter_ms(uint32_t timeout_ms)
virtual bool requires_GPS() const =0
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
LandStateType
Definition: defines.h:268
bool set_velocity(const Vector3f &velocity_neu)
const char * name() const override
Definition: mode.h:225
const char * name4() const override
Definition: mode.h:1168
bool is_autopilot() const override
Definition: mode.h:1009
const char * name() const override
Definition: mode.h:565
uint32_t wp_distance() const override
bool allows_arming(bool from_gcs) const override
Definition: mode.h:753
void set_roi(const Location &roi_location)
Definition: Parameters.h:7
int32_t wp_bearing() const override
heli_flags_t & heli_flags
Definition: mode.h:139
void set_mode_to_default(bool rtl)
bool has_manual_throttle() const override
Definition: mode.h:673
ThrowModeType
Definition: mode.h:1113
bool requires_GPS() const override
Definition: mode.h:243
bool has_manual_throttle() const override
Definition: mode.h:615
Definition: defines.h:218
bool requires_GPS() const override
Definition: mode.h:1006
AC_PosControl *& pos_control
Definition: mode.h:119
bool has_manual_throttle() const override
Definition: mode.h:178
uint32_t descend_start_timestamp
Definition: mode.h:382
bool init(bool ignore_checks) override
virtual bool init(bool ignore_checks) override
bool use_yaw_rate
Definition: mode_guided.cpp:26
bool requires_GPS() const override
Definition: mode.h:835
bool init(bool ignore_checks) override
const char * name() const override
Definition: mode.h:778
const char * name4() const override
Definition: mode.h:912
uint32_t last_log_ms
Definition: mode.h:1194
bool is_autopilot() const override
Definition: mode.h:754
const char * name() const override
Definition: mode.h:621
bool allows_arming(bool from_gcs) const override
Definition: mode.h:558
void set_fixed_yaw(float angle_deg, float turn_rate_dps, int8_t direction, bool relative_angle)
bool is_autopilot() const override
Definition: mode.h:907
const char * name4() const override
Definition: mode.h:956
bool requires_GPS() const override
Definition: mode.h:1158
void limit_init_time_and_pos()
Definition: defines.h:202
mode_reason_t
Definition: defines.h:115
bool landing_gear_should_be_deployed() const override
bool init(bool ignore_checks) override
const char * name4() const override
Definition: mode.h:566
Definition: Parameters.h:493
bool allows_arming(bool from_gcs) const override
Definition: mode.h:674
const char * name4() const override
Definition: mode.h:226
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)
bool requires_GPS() const override
Definition: mode.h:614
bool get_wp(Location_Class &loc) override
bool has_manual_throttle() const override
Definition: mode.h:865
bool is_autopilot() const override
Definition: mode.h:242
bool in_guided_mode() const
Definition: mode.h:246
bool requires_GPS() const override
Definition: mode.h:939
void update_simple_mode(void)
const char * name() const override
Definition: mode.h:680
bool init(bool ignore_checks) override
Location_Class return_target
Definition: mode.h:986
RC_Channel *& channel_roll
Definition: mode.h:124
const char * name() const override
Definition: mode.h:955
bool has_manual_throttle() const override
Definition: mode.h:244
bool set_mode(control_mode_t mode, mode_reason_t reason)
bool init(bool ignore_checks) override
Location_Class descent_target
Definition: mode.h:987
const char * name4() const override
Definition: mode.h:184
void land_run_horizontal_control()
float maximum
Definition: mode.h:539
float get_avoidance_adjusted_climbrate(float target_rate)
bool do_precision_loiter()
bool takeoff_start(float final_alt_above_home)
float get_non_takeoff_throttle(void)
bool is_autopilot() const override
Definition: mode.h:404
virtual const char * name4() const =0
void set_throttle_takeoff(void)
bool init(bool ignore_checks) override
bool requires_GPS() const override
Definition: mode.h:864
AP_AHRS & ahrs
Definition: mode.h:121
const char * name4() const override
Definition: mode.h:279
bool requires_GPS() const override
Definition: mode.h:751
bool init(bool ignore_checks) override
uint32_t hover_start_timestamp
Definition: mode.h:380
bool is_autopilot() const override
Definition: mode.h:643
bool allows_arming(bool from_gcs) const override
Definition: mode.h:642
float hover_throttle_level
Definition: mode.h:381
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1109
bool allows_arming(bool from_gcs) const override
Definition: mode.h:906
float descend_start_altitude
Definition: mode.h:385
void precision_loiter_xy()
bool land
Definition: mode.h:988
const char * name() const override
Definition: mode.h:1191
bool init(bool ignore_checks) override
virtual bool in_guided_mode() const
Definition: mode.h:97
bool requires_GPS() const override
Definition: mode.h:401
AC_AttitudeControl_t *& attitude_control
Definition: mode.h:122
bool has_manual_throttle() const override
Definition: mode.h:1067
static const struct AP_Param::GroupInfo var_info[]
Definition: mode.h:677
const char * name() const override
Definition: mode.h:1073
void circle_movetoedge_start(const Location_Class &circle_center, float radius_m)
float & ekfNavVelGainScaler
Definition: mode.h:136
bool requires_GPS() const override
Definition: mode.h:585
static AutoYaw auto_yaw
Definition: mode.h:72
const char * name() const override
Definition: mode.h:875
virtual void run() override
Definition: defines.h:195
bool is_autopilot() const override
Definition: mode.h:221
bool has_manual_throttle() const override
Definition: mode.h:752
LEVEL_ISSUE issue
Definition: mode.h:538
bool init(bool ignore_checks) override
bool is_autopilot() const override
Definition: mode.h:1069
autopilot_yaw_mode mode() const
Definition: mode.h:25
PayloadPlaceStateType state
Definition: mode.h:379
bool init(bool ignore_checks) override
virtual bool is_autopilot() const
Definition: mode.h:79
bool has_manual_throttle() const override
Definition: mode.h:1007
bool allows_arming(bool from_gcs) const override
Definition: mode.h:813
bool is_autopilot() const override
Definition: mode.h:176
bool allows_arming(bool from_gcs) const override
Definition: mode.h:587
bool is_autopilot() const override
Definition: mode.h:867
AC_Loiter *& loiter_nav
Definition: mode.h:118
bool requires_GPS() const override
Definition: mode.h:177
bool allows_arming(bool from_gcs) const override
Definition: mode.h:179
void zero_throttle_and_relax_ac()
bool init(bool ignore_checks) override
bool init(bool ignore_checks) override
float & G_Dt
Definition: mode.h:128
bool landing_gear_should_be_deployed() const override
float current
Definition: mode.h:540
Definition: defines.h:275
uint32_t wp_distance() const override
const char * name4() const override
Definition: mode.h:1121
Location_Class climb_target
Definition: mode.h:985
void set_rate(float new_rate_cds)
AutoMode
Definition: defines.h:194
const char * name4() const override
Definition: mode.h:779
int32_t wp_bearing() const override
void set_land_complete(bool b)
bool has_manual_throttle() const override
Definition: mode.h:219
bool allows_arming(bool from_gcs) const override
Definition: mode.h:941
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
void restart_without_terrain()
PayloadPlaceStateType
Definition: defines.h:273
bool requires_GPS() const override
Definition: mode.h:1107
bool requires_GPS() const override
Definition: mode.h:904
void run() override
Definition: mode.h:934
void set_mode(autopilot_yaw_mode new_mode)
bool takeoff_triggered(float target_climb_rate) const
const char * name() const override
Definition: mode.h:278
const char * name4() const override
Definition: mode.h:876
MOTOR_CLASS *& motors
Definition: mode.h:123
uint32_t wp_distance() const override
AP_InertialNav & inertial_nav
Definition: mode.h:120
bool allows_arming(bool from_gcs) const override
Definition: mode.h:403
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
const char * name4() const override
Definition: mode.h:681
uint32_t wp_distance() const override
void set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads)
bool has_manual_throttle() const override
Definition: mode.h:812
bool terrain_used
Definition: mode.h:989
bool allows_arming(bool from_gcs) const override
Definition: mode.h:1160
void set_precision_loiter_enabled(bool value)
Definition: mode.h:870
uint32_t wp_distance() const override
void payload_place_start()
bool requires_GPS() const override
Definition: mode.h:1066
GuidedMode
Definition: defines.h:208
bool has_manual_throttle() const override
Definition: mode.h:1159
Location_Class origin_point
Definition: mode.h:984
const char * name() const override
Definition: mode.h:592
bool has_manual_throttle() const override
Definition: mode.h:586
bool has_manual_throttle() const override
Definition: mode.h:940
float climb_rate_cms
Definition: mode_guided.cpp:25
bool verify_command_callback(const AP_Mission::Mission_Command &cmd)
float descend_throttle_level
Definition: mode.h:384
bool init(bool ignore_checks) override
virtual void run_autopilot()
Definition: mode.h:93
bool has_manual_throttle() const override
Definition: mode.h:1043
bool start_command(const AP_Mission::Mission_Command &cmd)
const char * name4() const override
Definition: mode.h:819
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)
bool allows_arming(bool from_gcs) const override
Definition: mode.h:245
void takeoff_timer_start(float alt_cm)
virtual const char * name() const =0
bool is_autopilot() const override
Definition: mode.h:588
const char * name4() const override
Definition: mode.h:413
void Log_Write_Event(uint8_t id)
const char * name() const override
Definition: mode.h:845
virtual bool init(bool ignore_checks) override
void set_descent_target_alt(uint32_t alt)
Definition: mode.h:966
void angle_control_start()
bool has_manual_throttle() const override
Definition: mode.h:1185
const char * name() const override
Definition: mode.h:1167
bool init(bool ignore_checks) override
takeoff_state_t & takeoff_state
Definition: mode.h:130
virtual bool has_manual_throttle() const =0
AC_WPNav *& wp_nav
Definition: mode.h:117
virtual void run() override
void land_run_vertical_control(bool pause_descent=false)
bool init(bool ignore_checks) override
uint16_t get_pilot_speed_dn(void)
float yaw_cd
Definition: mode_guided.cpp:23
bool requires_GPS() const override
Definition: mode.h:1184
bool requires_GPS() const override
Definition: mode.h:1042
void limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm)
bool is_autopilot() const override
Definition: mode.h:814
int32_t wp_bearing() const override
autopilot_yaw_mode
Definition: defines.h:14
const char * name4() const override
Definition: mode.h:648
bool is_autopilot() const override
Definition: mode.h:1045
Parameters & g
Definition: mode.h:115
autopilot_yaw_mode default_mode(bool rtl) const
int32_t wp_bearing() const override
const char * name() const override
Definition: mode.h:183
bool allows_arming(bool from_gcs) const override
Definition: mode.h:866
bool is_autopilot() const override
Definition: mode.h:1110
float descend_max
Definition: mode.h:386
bool has_manual_throttle() const override
Definition: mode.h:836
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
const char * name4() const override
Definition: mode.h:622
const char * name4() const override
Definition: mode.h:1017
Definition: AP_Arming.h:5
GuidedMode mode() const
Definition: mode.h:771
bool has_manual_throttle() const override
Definition: mode.h:402
int32_t wp_bearing() const override
bool requires_GPS() const override
Definition: mode.h:672
virtual uint32_t wp_distance() const
Definition: mode.h:94
bool is_autopilot() const override
Definition: mode.h:559
const char * name() const override
Definition: mode.h:911
bool init(bool ignore_checks) override
const char * name() const override
Definition: mode.h:818
bool state_complete()
Definition: mode.h:947
void takeoff_start(const Location &dest_loc)
void land_run(bool disarm_on_land)
bool has_manual_throttle() const override
Definition: mode.h:557
const char * name4() const override
Definition: mode.h:1192
ap_t & ap
Definition: mode.h:129
#define MOTOR_CLASS
Definition: Copter.h:412
bool requires_GPS() const override
Definition: mode.h:218
virtual int32_t wp_bearing() const
Definition: mode.h:95
const char * name() const override
Definition: mode.h:412
uint32_t wp_distance() const override
int32_t wp_bearing() const override
Definition: defines.h:228
ParametersG2 & g2
Definition: mode.h:116
bool requires_GPS() const override
Definition: mode.h:811
bool init(bool ignore_checks) override
int32_t get_alt_above_ground(void)
float yaw_rate_cds
Definition: mode_guided.cpp:24
SmartRTLState
Definition: defines.h:226
bool allows_arming(bool from_gcs) const override
Definition: mode.h:837
bool landing_gear_should_be_deployed() const override
Definition: mode.h:839
bool requires_GPS() const override
Definition: mode.h:640
RC_Channel *& channel_yaw
Definition: mode.h:127
const char * name() const override
Definition: mode.h:1120
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)
RC_Channel *& channel_throttle
Definition: mode.h:126
bool init(bool ignore_checks) override
bool allows_arming(bool from_gcs) const override
Definition: mode.h:220
RC_Channel *& channel_pitch
Definition: mode.h:125
const char * name4() const override
Definition: mode.h:593
Definition: GCS_Mavlink.h:8
void run_autopilot() override
const char * name4() const override
Definition: mode.h:1074