#pragma once12#include "Rover.h"34// pre-define ModeRTL so Auto can appear higher in this file5class ModeRTL;67class Mode8{9public:1011// Auto Pilot modes12// ----------------13enum class Number : uint8_t {14MANUAL = 0,15ACRO = 1,16STEERING = 3,17HOLD = 4,18LOITER = 5,19FOLLOW = 6,20SIMPLE = 7,21#if MODE_DOCK_ENABLED22DOCK = 8,23#endif24CIRCLE = 9,25AUTO = 10,26RTL = 11,27SMART_RTL = 12,28GUIDED = 15,29INITIALISING = 16,30// Mode number 30 reserved for "offboard" for external/lua control.31};3233// Constructor34Mode();3536// do not allow copying37CLASS_NO_COPY(Mode);3839// enter this mode, returns false if we failed to enter40bool enter();4142// perform any cleanups required:43void exit();4445// returns a unique number specific to this mode46virtual Number mode_number() const = 0;4748// returns full text name49virtual const char *name() const = 0;5051// returns short text name (up to 4 bytes)52virtual const char *name4() const = 0;5354//55// methods that sub classes should override to affect movement of the vehicle in this mode56//5758// convert user input to targets, implement high level control for this mode59virtual void update() = 0;6061//62// attributes of the mode63//6465// return if in non-manual mode : Auto, Guided, RTL, SmartRTL66virtual bool is_autopilot_mode() const { return false; }6768// return if external control is allowed in this mode (Guided or Guided-within-Auto)69virtual bool in_guided_mode() const { return false; }7071// returns true if vehicle can be armed or disarmed from the transmitter in this mode72virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }7374// returns false if vehicle cannot be armed in this mode75virtual bool allows_arming() const { return true; }7677bool allows_stick_mixing() const { return is_autopilot_mode(); }7879//80// attributes for mavlink system status reporting81//8283// returns true if any RC input is used84virtual bool has_manual_input() const { return false; }8586// true if heading is controlled87virtual bool attitude_stabilized() const { return true; }8889// true if mode requires position and/or velocity estimate90virtual bool requires_position() const { return true; }91virtual bool requires_velocity() const { return true; }9293// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)94virtual float wp_bearing() const;95virtual float nav_bearing() const;96virtual float crosstrack_error() const;97virtual float get_desired_lat_accel() const;9899// get speed error in m/s, not currently supported100float speed_error() const { return 0.0f; }101102//103// navigation methods104//105106// return distance (in meters) to destination107virtual float get_distance_to_destination() const { return 0.0f; }108109// return desired location (used in Guided, Auto, RTL, etc)110// return true on success, false if there is no valid destination111virtual bool get_desired_location(Location& destination) const WARN_IF_UNUSED { return false; }112113// set desired location (used in Guided, Auto)114// set next_destination (if known). If not provided vehicle stops at destination115virtual bool set_desired_location(const Location &destination, Location next_destination = Location()) WARN_IF_UNUSED;116117// 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 stuck118virtual bool reached_destination() const { return true; }119120// get default speed for this mode (held in CRUISE_SPEED, WP_SPEED or RTL_SPEED)121// rtl argument should be true if called from RTL or SmartRTL modes (handled here to avoid duplication)122float get_speed_default(bool rtl = false) const;123124// set desired speed in m/s125virtual bool set_desired_speed(float speed_ms) { return false; }126127// execute the mission in reverse (i.e. backing up)128void set_reversed(bool value);129130// init reversed flag for autopilot mode131virtual void init_reversed_flag() { if (is_autopilot_mode()) { set_reversed(false); } }132133// handle tacking request (from auxiliary switch) in sailboats134virtual void handle_tack_request();135136protected:137138// subclasses override this to perform checks before entering the mode139virtual bool _enter() { return true; }140141// subclasses override this to perform any required cleanup when exiting the mode142virtual void _exit() { return; }143144// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments145// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise146// throttle_out is in the range -100 ~ +100147void get_pilot_desired_steering_and_throttle(float &steering_out, float &throttle_out) const;148149// decode pilot input steering and return steering_out and speed_out (in m/s)150void get_pilot_desired_steering_and_speed(float &steering_out, float &speed_out) const;151152// decode pilot lateral movement input and return in lateral_out argument153void get_pilot_desired_lateral(float &lateral_out) const;154155// decode pilot's input and return heading_out (in cd) and speed_out (in m/s)156void get_pilot_desired_heading_and_speed(float &heading_out, float &speed_out) const;157158// decode pilot roll and pitch inputs and return in roll_out and pitch_out arguments159// outputs are in the range -1 to +1160void get_pilot_desired_roll_and_pitch(float &roll_out, float &pitch_out) const;161162// decode pilot height inputs and return in height_out arguments163// outputs are in the range -1 to +1164void get_pilot_desired_walking_height(float &walking_height_out) const;165166// high level call to navigate to waypoint167void navigate_to_waypoint();168169// calculate steering output given a turn rate170// desired turn rate in radians/sec. Positive to the right.171void calc_steering_from_turn_rate(float turn_rate);172173// calculate steering angle given a desired lateral acceleration174void calc_steering_from_lateral_acceleration(float lat_accel, bool reversed = false);175176// calculate steering output to drive towards desired heading177// rate_max is a maximum turn rate in deg/s. set to zero to use default turn rate limits178void calc_steering_to_heading(float desired_heading_cd, float rate_max_degs = 0.0f);179180// calculates the amount of throttle that should be output based181// on things like proximity to corners and current speed182virtual void calc_throttle(float target_speed, bool avoidance_enabled);183184// performs a controlled stop. returns true once vehicle has stopped185bool stop_vehicle();186187// estimate maximum vehicle speed (in m/s)188// cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1189float calc_speed_max(float cruise_speed, float cruise_throttle) const;190191// calculate pilot input to nudge speed up or down192// target_speed should be in meters/sec193// 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 down194float calc_speed_nudge(float target_speed, bool reversed);195196protected:197198// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments199// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise200// throttle_out is in the range -100 ~ +100201void get_pilot_input(float &steering_out, float &throttle_out) const;202void set_steering(float steering_value);203204// references to avoid code churn:205class AP_AHRS &ahrs;206class Parameters &g;207class ParametersG2 &g2;208class RC_Channel *&channel_steer;209class RC_Channel *&channel_throttle;210class RC_Channel *&channel_lateral;211class RC_Channel *&channel_roll;212class RC_Channel *&channel_pitch;213class RC_Channel *&channel_walking_height;214class AR_AttitudeControl &attitude_control;215216// private members for waypoint navigation217float _distance_to_destination; // distance from vehicle to final destination in meters218bool _reached_destination; // true once the vehicle has reached the destination219float _desired_yaw_cd; // desired yaw in centi-degrees. used in Auto, Guided and Loiter220};221222223class ModeAcro : public Mode224{225public:226227Number mode_number() const override { return Number::ACRO; }228const char *name() const override { return "Acro"; }229const char *name4() const override { return "ACRO"; }230231// methods that affect movement of the vehicle in this mode232void update() override;233234// attributes for mavlink system status reporting235bool has_manual_input() const override { return true; }236237// acro mode requires a velocity estimate for non skid-steer rovers238bool requires_position() const override { return false; }239bool requires_velocity() const override;240241// sailboats in acro mode support user manually initiating tacking from transmitter242void handle_tack_request() override;243};244245246class ModeAuto : public Mode247{248public:249250Number mode_number() const override { return Number::AUTO; }251const char *name() const override { return "Auto"; }252const char *name4() const override { return "AUTO"; }253254// methods that affect movement of the vehicle in this mode255void update() override;256void calc_throttle(float target_speed, bool avoidance_enabled) override;257258// attributes of the mode259bool is_autopilot_mode() const override { return true; }260261// return if external control is allowed in this mode (Guided or Guided-within-Auto)262bool in_guided_mode() const override { return _submode == SubMode::Guided || _submode == SubMode::NavScriptTime; }263264// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)265float wp_bearing() const override;266float nav_bearing() const override;267float crosstrack_error() const override;268float get_desired_lat_accel() const override;269270// return distance (in meters) to destination271float get_distance_to_destination() const override;272273// get or set desired location274bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;275bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED;276bool reached_destination() const override;277278// set desired speed in m/s279bool set_desired_speed(float speed_ms) override;280281// start RTL (within auto)282void start_RTL();283284// lua accessors for nav script time support285bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4);286void nav_script_time_done(uint16_t id);287288//289void init_reversed_flag() override {290if (!mission.is_resume()) {291set_reversed(false);292}293}294295AP_Mission mission{296FUNCTOR_BIND_MEMBER(&ModeAuto::start_command, bool, const AP_Mission::Mission_Command&),297FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&),298FUNCTOR_BIND_MEMBER(&ModeAuto::exit_mission, void)};299300enum class DoneBehaviour : uint8_t {301HOLD = 0,302LOITER = 1,303ACRO = 2,304MANUAL = 3,305};306307protected:308309bool _enter() override;310void _exit() override;311312enum SubMode: uint8_t {313WP, // drive to a given location314HeadingAndSpeed, // turn to a given heading315RTL, // perform RTL within auto mode316Loiter, // perform Loiter within auto mode317Guided, // handover control to external navigation system from within auto mode318Stop, // stop the vehicle as quickly as possible319NavScriptTime, // accept targets from lua scripts while NAV_SCRIPT_TIME commands are executing320Circle, // circle a given location321} _submode;322323private:324325bool check_trigger(void);326bool start_loiter();327void start_guided(const Location& target_loc);328void start_stop();329void send_guided_position_target();330331bool start_command(const AP_Mission::Mission_Command& cmd);332void exit_mission();333bool verify_command_callback(const AP_Mission::Mission_Command& cmd);334335bool verify_command(const AP_Mission::Mission_Command& cmd);336void do_RTL(void);337bool do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination);338void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);339void do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd);340void do_nav_delay(const AP_Mission::Mission_Command& cmd);341bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);342bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);343bool verify_RTL() const;344bool verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd);345bool verify_loiter_time(const AP_Mission::Mission_Command& cmd);346bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);347bool verify_nav_set_yaw_speed();348bool do_circle(const AP_Mission::Mission_Command& cmd);349bool verify_circle(const AP_Mission::Mission_Command& cmd);350void do_wait_delay(const AP_Mission::Mission_Command& cmd);351void do_within_distance(const AP_Mission::Mission_Command& cmd);352bool verify_wait_delay();353bool verify_within_distance();354void do_change_speed(const AP_Mission::Mission_Command& cmd);355void do_set_home(const AP_Mission::Mission_Command& cmd);356void do_set_reverse(const AP_Mission::Mission_Command& cmd);357void do_guided_limits(const AP_Mission::Mission_Command& cmd);358#if AP_SCRIPTING_ENABLED359void do_nav_script_time(const AP_Mission::Mission_Command& cmd);360bool verify_nav_script_time();361#endif362363bool waiting_to_start; // true if waiting for EKF origin before starting mission364bool auto_triggered; // true when auto has been triggered to start365366// HeadingAndSpeed sub mode variables367float _desired_speed; // desired speed in HeadingAndSpeed submode368bool _reached_heading; // true when vehicle has reached desired heading in TurnToHeading sub mode369370// Loiter control371uint16_t loiter_duration; // How long we should loiter at the nav_waypoint (time in seconds)372uint32_t loiter_start_time; // How long have we been loitering - The start time in millis373bool previously_reached_wp; // set to true if we have EVER reached the waypoint374375// Guided-within-Auto variables376struct {377Location loc; // location target sent to external navigation378bool valid; // true if loc is valid379uint32_t last_sent_ms; // system time that target was last sent to offboard navigation380} guided_target;381382// Conditional command383// A value used in condition commands (eg delay, change alt, etc.)384// For example in a change altitude command, it is the altitude to change to.385int32_t condition_value;386// A starting value used to check the status of a conditional command.387// For example in a delay command the condition_start records that start time for the delay388int32_t condition_start;389390// Delay the next navigation command391uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands392uint32_t nav_delay_time_start_ms;393394#if AP_SCRIPTING_ENABLED395// nav_script_time command variables396struct {397bool done; // true once lua script indicates it has completed398uint16_t id; // unique id to avoid race conditions between commands and lua scripts399uint32_t start_ms; // system time nav_script_time command was received (used for timeout)400uint8_t command; // command number provided by mission command401uint8_t timeout_s; // timeout (in seconds) provided by mission command402float arg1; // 1st argument provided by mission command403float arg2; // 2nd argument provided by mission command404int16_t arg3; // 3rd argument provided by mission command405int16_t arg4; // 4th argument provided by mission command406} nav_scripting;407#endif408409// Mission change detector410AP_Mission_ChangeDetector mis_change_detector;411};412413class ModeCircle : public Mode414{415public:416417// need a constructor for parameters418ModeCircle();419420// Does not allow copies421CLASS_NO_COPY(ModeCircle);422423Number mode_number() const override { return Number::CIRCLE; }424const char *name() const override { return "Circle"; }425const char *name4() const override { return "CIRC"; }426427// return the distance at which the vehicle is considered to be on track along the circle428float get_reached_distance() const;429430// initialise with specific center location, radius (in meters) and direction431// replaces use of _enter when initialised from within Auto mode432bool set_center(const Location& center_loc, float radius_m, bool dir_ccw);433434// methods that affect movement of the vehicle in this mode435void update() override;436437bool is_autopilot_mode() const override { return true; }438439// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)440float wp_bearing() const override;441float nav_bearing() const override;442float crosstrack_error() const override { return dist_to_edge_m; }443float get_desired_lat_accel() const override;444445// set desired speed in m/s446bool set_desired_speed(float speed_ms) override;447448// return distance (in meters) to destination449float get_distance_to_destination() const override { return _distance_to_destination; }450451// get or set desired location452bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;453454// return total angle in radians that vehicle has circled455// fabsf is used so that full rotations in either direction are counted456float get_angle_total_rad() const { return fabsf(angle_total_rad); }457458static const struct AP_Param::GroupInfo var_info[];459460protected:461462AP_Float radius; // circle radius in meters463AP_Float speed; // vehicle speed in m/s. If zero uses WP_SPEED464AP_Int8 direction; // direction 0:clockwise, 1:counter-clockwise465466// initialise mode467bool _enter() override;468469// Update position controller targets driving to the circle edge470void update_drive_to_radius();471472// Update position controller targets while circling473void update_circling();474475// initialise target_yaw_rad using the vehicle's position and yaw476// if there is no current position estimate target_yaw_rad is set to vehicle yaw477void init_target_yaw_rad();478479// limit config speed so that lateral acceleration is within limits480// outputs warning to user if speed is reduced481void check_config_speed();482483// ensure config radius is no smaller then vehicle's TURN_RADIUS484// radius is increased if necessary and warning is output to the user485void check_config_radius();486487// enum for Direction parameter488enum class Direction {489CW = 0,490CCW = 1491};492493// local members494struct {495Location center_loc; // circle center as a Location496Vector2f center_pos; // circle center as an offset (in meters) from the EKF origin497float radius; // circle radius498float speed; // desired speed around circle in m/s499Direction dir; // direction, 0:clockwise, 1:counter-clockwise500} config;501struct {502float speed; // vehicle's target speed around circle in m/s503float yaw_rad; // earth-frame angle of tarrget point on the circle504Vector2p pos; // latest position target sent to position controller505Vector2f vel; // latest velocity target sent to position controller506Vector2f accel; // latest accel target sent to position controller507} target;508float angle_total_rad; // total angle in radians that vehicle has circled509bool reached_edge; // true once vehicle has reached edge of circle510float dist_to_edge_m; // distance to edge of circle in meters (equivalent to crosstrack error)511bool tracking_back; // true if the vehicle is trying to track back onto the circle512};513514class ModeGuided : public Mode515{516public:517#if AP_EXTERNAL_CONTROL_ENABLED518friend class AP_ExternalControl_Rover;519#endif520521Number mode_number() const override { return Number::GUIDED; }522const char *name() const override { return "Guided"; }523const char *name4() const override { return "GUID"; }524525// methods that affect movement of the vehicle in this mode526void update() override;527528// attributes of the mode529bool is_autopilot_mode() const override { return true; }530531// return if external control is allowed in this mode (Guided or Guided-within-Auto)532bool in_guided_mode() const override { return true; }533534// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)535float wp_bearing() const override;536float nav_bearing() const override;537float crosstrack_error() const override;538float get_desired_lat_accel() const override;539540// return distance (in meters) to destination541float get_distance_to_destination() const override;542543// return true if vehicle has reached destination544bool reached_destination() const override;545546// set desired speed in m/s547bool set_desired_speed(float speed_ms) override;548549// get or set desired location550bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;551bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED;552553// set desired heading and speed554void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed);555556// set desired heading-delta, turn-rate and speed557void set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed);558void set_desired_turn_rate_and_speed(float turn_rate_cds, float target_speed);559560// set steering and throttle (-1 to +1). Only called from scripts561void set_steering_and_throttle(float steering, float throttle);562563// vehicle start loiter564bool start_loiter();565566// start stopping567void start_stop();568569// guided limits570void limit_set(uint32_t timeout_ms, float horiz_max);571void limit_clear();572void limit_init_time_and_location();573bool limit_breached() const;574575protected:576577enum class SubMode: uint8_t {578WP,579HeadingAndSpeed,580TurnRateAndSpeed,581Loiter,582SteeringAndThrottle,583Stop584};585586// enum for GUID_OPTIONS parameter587enum class Options : int32_t {588SCurvesUsedForNavigation = (1U << 6)589};590591bool _enter() override;592593// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping594// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping)595bool use_scurves_for_navigation() const;596597SubMode _guided_mode; // stores which GUIDED mode the vehicle is in598599// attitude control600bool have_attitude_target; // true if we have a valid attitude target601uint32_t _des_att_time_ms; // system time last call to set_desired_attitude was made (used for timeout)602float _desired_yaw_rate_cds;// target turn rate centi-degrees per second603bool send_notification; // used to send one time notification to ground station604float _desired_speed; // desired speed used only in HeadingAndSpeed submode605606// direct steering and throttle control607bool _have_strthr; // true if we have a valid direct steering and throttle inputs608uint32_t _strthr_time_ms; // system time last call to set_steering_and_throttle was made (used for timeout)609float _strthr_steering; // direct steering input in the range -1 to +1610float _strthr_throttle; // direct throttle input in the range -1 to +1611612// limits613struct {614uint32_t timeout_ms;// timeout from the time that guided is invoked615float horiz_max; // horizontal position limit in meters from where guided mode was initiated (0 = no limit)616uint32_t start_time_ms; // system time in milliseconds that control was handed to the external computer617Location start_loc; // starting location for checking horiz_max limit618} limit;619};620621622class ModeHold : public Mode623{624public:625626Number mode_number() const override { return Number::HOLD; }627const char *name() const override { return "Hold"; }628const char *name4() const override { return "HOLD"; }629630// methods that affect movement of the vehicle in this mode631void update() override;632633// attributes for mavlink system status reporting634bool attitude_stabilized() const override { return false; }635636// hold mode does not require position or velocity estimate637bool requires_position() const override { return false; }638bool requires_velocity() const override { return false; }639};640641class ModeLoiter : public Mode642{643public:644645Number mode_number() const override { return Number::LOITER; }646const char *name() const override { return "Loiter"; }647const char *name4() const override { return "LOIT"; }648649// methods that affect movement of the vehicle in this mode650void update() override;651652// attributes of the mode653bool is_autopilot_mode() const override { return true; }654655// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)656float wp_bearing() const override { return _desired_yaw_cd * 0.01f; }657float nav_bearing() const override { return _desired_yaw_cd * 0.01f; }658float crosstrack_error() const override { return 0.0f; }659660// return desired location661bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;662663// return distance (in meters) to destination664float get_distance_to_destination() const override { return _distance_to_destination; }665666protected:667668bool _enter() override;669670Location _destination; // target location to hold position around671float _desired_speed; // desired speed (ramped down from initial speed to zero)672};673674class ModeManual : public Mode675{676public:677678Number mode_number() const override { return Number::MANUAL; }679const char *name() const override { return "Manual"; }680const char *name4() const override { return "MANU"; }681682// methods that affect movement of the vehicle in this mode683void update() override;684685// attributes for mavlink system status reporting686bool has_manual_input() const override { return true; }687bool attitude_stabilized() const override { return false; }688689// manual mode does not require position or velocity estimate690bool requires_position() const override { return false; }691bool requires_velocity() const override { return false; }692693protected:694695void _exit() override;696};697698699class ModeRTL : public Mode700{701public:702703Number mode_number() const override { return Number::RTL; }704const char *name() const override { return "RTL"; }705const char *name4() const override { return "RTL"; }706707// methods that affect movement of the vehicle in this mode708void update() override;709710// attributes of the mode711bool is_autopilot_mode() const override { return true; }712713// do not allow arming from this mode714bool allows_arming() const override { return false; }715716// return desired location717bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;718719// return distance (in meters) to destination720float get_distance_to_destination() const override { return _distance_to_destination; }721bool reached_destination() const override;722723// set desired speed in m/s724bool set_desired_speed(float speed_ms) override;725726protected:727728bool _enter() override;729730bool send_notification; // used to send one time notification to ground station731bool _loitering; // true if loitering at end of RTL732733};734735class ModeSmartRTL : public Mode736{737public:738739Number mode_number() const override { return Number::SMART_RTL; }740const char *name() const override { return "Smart RTL"; }741const char *name4() const override { return "SRTL"; }742743// methods that affect movement of the vehicle in this mode744void update() override;745746// attributes of the mode747bool is_autopilot_mode() const override { return true; }748749// do not allow arming from this mode750bool allows_arming() const override { return false; }751752// return desired location753bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;754755// return distance (in meters) to destination756float get_distance_to_destination() const override { return _distance_to_destination; }757bool reached_destination() const override { return smart_rtl_state == SmartRTLState::StopAtHome; }758759// set desired speed in m/s760bool set_desired_speed(float speed_ms) override;761762// save current position for use by the smart_rtl flight mode763void save_position();764765protected:766767// Safe RTL states768enum class SmartRTLState: uint8_t {769WaitForPathCleanup,770PathFollow,771StopAtHome,772Failure773} smart_rtl_state;774775bool _enter() override;776bool _load_point;777bool _loitering; // true if loitering at end of SRTL778};779780781782class ModeSteering : public Mode783{784public:785786Number mode_number() const override { return Number::STEERING; }787const char *name() const override { return "Steering"; }788const char *name4() const override { return "STER"; }789790// methods that affect movement of the vehicle in this mode791void update() override;792793// attributes for mavlink system status reporting794bool has_manual_input() const override { return true; }795796// steering requires velocity but not position797bool requires_position() const override { return false; }798bool requires_velocity() const override { return true; }799800// return desired lateral acceleration801float get_desired_lat_accel() const override { return _desired_lat_accel; }802803private:804805float _desired_lat_accel; // desired lateral acceleration calculated from pilot steering input806};807808class ModeInitializing : public Mode809{810public:811812Number mode_number() const override { return Number::INITIALISING; }813const char *name() const override { return "Initialising"; }814const char *name4() const override { return "INIT"; }815816// methods that affect movement of the vehicle in this mode817void update() override { }818819// do not allow arming from this mode820bool allows_arming() const override { return false; }821822// attributes for mavlink system status reporting823bool has_manual_input() const override { return true; }824bool attitude_stabilized() const override { return false; }825protected:826bool _enter() override { return false; };827};828829#if MODE_FOLLOW_ENABLED830class ModeFollow : public Mode831{832public:833834Number mode_number() const override { return Number::FOLLOW; }835const char *name() const override { return "Follow"; }836const char *name4() const override { return "FOLL"; }837838// methods that affect movement of the vehicle in this mode839void update() override;840841// attributes of the mode842bool is_autopilot_mode() const override { return true; }843844// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)845float wp_bearing() const override;846float nav_bearing() const override { return wp_bearing(); }847float crosstrack_error() const override { return 0.0f; }848849// return desired location850bool get_desired_location(Location& destination) const override WARN_IF_UNUSED { return false; }851852// return distance (in meters) to destination853float get_distance_to_destination() const override;854855// set desired speed in m/s856bool set_desired_speed(float speed_ms) override;857858protected:859860bool _enter() override;861void _exit() override;862863float _desired_speed; // desired speed in m/s864};865#endif866867class ModeSimple : public Mode868{869public:870871Number mode_number() const override { return Number::SIMPLE; }872const char *name() const override { return "Simple"; }873const char *name4() const override { return "SMPL"; }874875// methods that affect movement of the vehicle in this mode876void update() override;877void init_heading();878879// simple type enum used for SIMPLE_TYPE parameter880enum simple_type {881Simple_InitialHeading = 0,882Simple_CardinalDirections = 1,883};884885private:886887float _initial_heading_cd; // vehicle heading (in centi-degrees) at moment vehicle was armed888float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot889};890891#if MODE_DOCK_ENABLED892class ModeDock : public Mode893{894public:895896// need a constructor for parameters897ModeDock(void);898899// Does not allow copies900CLASS_NO_COPY(ModeDock);901902Number mode_number() const override { return Number::DOCK; }903const char *name() const override { return "Dock"; }904const char *name4() const override { return "DOCK"; }905906// methods that affect movement of the vehicle in this mode907void update() override;908909bool is_autopilot_mode() const override { return true; }910911// return distance (in meters) to destination912float get_distance_to_destination() const override { return _distance_to_destination; }913914static const struct AP_Param::GroupInfo var_info[];915916protected:917918AP_Float speed; // dock mode speed919AP_Float desired_dir; // desired direction of approach920AP_Int8 hdg_corr_enable; // enable heading correction921AP_Float hdg_corr_weight; // heading correction weight922AP_Float stopping_dist; // how far away from the docking target should we start stopping923924bool _enter() override;925926// return reduced speed of vehicle based on error in position and current distance from the dock927float apply_slowdown(float desired_speed);928929// calculate position of dock relative to the vehicle930bool calc_dock_pos_rel_vehicle_NE_m(Vector2f &dock_pos_rel_vehicle_m) const;931932// we force the vehicle to use real dock target vector when this much close to the docking station933const float _force_real_target_limit_m = 3.0f;934// acceptable lateral error in vehicle's position with respect to dock. This is used while slowing down the vehicle935const float _acceptable_pos_error_m = 0.2f;936937Vector2p _dock_pos_rel_origin_m; // position vector towards docking target relative to ekf origin938Vector2f _desired_heading_NE; // unit vector in desired direction of docking939bool _docking_complete = false; // flag to mark docking complete when we are close enough to the dock940bool _loitering = false; // true if we are loitering after mission completion941};942#endif943944945