Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/mode.h
Views: 1798
#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 short text name (up to 4 bytes)49virtual const char *name4() const = 0;5051//52// methods that sub classes should override to affect movement of the vehicle in this mode53//5455// convert user input to targets, implement high level control for this mode56virtual void update() = 0;5758//59// attributes of the mode60//6162// return if in non-manual mode : Auto, Guided, RTL, SmartRTL63virtual bool is_autopilot_mode() const { return false; }6465// return if external control is allowed in this mode (Guided or Guided-within-Auto)66virtual bool in_guided_mode() const { return false; }6768// returns true if vehicle can be armed or disarmed from the transmitter in this mode69virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }7071// returns false if vehicle cannot be armed in this mode72virtual bool allows_arming() const { return true; }7374bool allows_stick_mixing() const { return is_autopilot_mode(); }7576//77// attributes for mavlink system status reporting78//7980// returns true if any RC input is used81virtual bool has_manual_input() const { return false; }8283// true if heading is controlled84virtual bool attitude_stabilized() const { return true; }8586// true if mode requires position and/or velocity estimate87virtual bool requires_position() const { return true; }88virtual bool requires_velocity() const { return true; }8990// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)91virtual float wp_bearing() const;92virtual float nav_bearing() const;93virtual float crosstrack_error() const;94virtual float get_desired_lat_accel() const;9596// get speed error in m/s, not currently supported97float speed_error() const { return 0.0f; }9899//100// navigation methods101//102103// return distance (in meters) to destination104virtual float get_distance_to_destination() const { return 0.0f; }105106// return desired location (used in Guided, Auto, RTL, etc)107// return true on success, false if there is no valid destination108virtual bool get_desired_location(Location& destination) const WARN_IF_UNUSED { return false; }109110// set desired location (used in Guided, Auto)111// set next_destination (if known). If not provided vehicle stops at destination112virtual bool set_desired_location(const Location &destination, Location next_destination = Location()) WARN_IF_UNUSED;113114// 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 stuck115virtual bool reached_destination() const { return true; }116117// get default speed for this mode (held in CRUISE_SPEED, WP_SPEED or RTL_SPEED)118// rtl argument should be true if called from RTL or SmartRTL modes (handled here to avoid duplication)119float get_speed_default(bool rtl = false) const;120121// set desired speed in m/s122virtual bool set_desired_speed(float speed) { return false; }123124// execute the mission in reverse (i.e. backing up)125void set_reversed(bool value);126127// init reversed flag for autopilot mode128virtual void init_reversed_flag() { if (is_autopilot_mode()) { set_reversed(false); } }129130// handle tacking request (from auxiliary switch) in sailboats131virtual void handle_tack_request();132133protected:134135// subclasses override this to perform checks before entering the mode136virtual bool _enter() { return true; }137138// subclasses override this to perform any required cleanup when exiting the mode139virtual void _exit() { return; }140141// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments142// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise143// throttle_out is in the range -100 ~ +100144void get_pilot_desired_steering_and_throttle(float &steering_out, float &throttle_out) const;145146// decode pilot input steering and return steering_out and speed_out (in m/s)147void get_pilot_desired_steering_and_speed(float &steering_out, float &speed_out) const;148149// decode pilot lateral movement input and return in lateral_out argument150void get_pilot_desired_lateral(float &lateral_out) const;151152// decode pilot's input and return heading_out (in cd) and speed_out (in m/s)153void get_pilot_desired_heading_and_speed(float &heading_out, float &speed_out) const;154155// decode pilot roll and pitch inputs and return in roll_out and pitch_out arguments156// outputs are in the range -1 to +1157void get_pilot_desired_roll_and_pitch(float &roll_out, float &pitch_out) const;158159// decode pilot height inputs and return in height_out arguments160// outputs are in the range -1 to +1161void get_pilot_desired_walking_height(float &walking_height_out) const;162163// high level call to navigate to waypoint164void navigate_to_waypoint();165166// calculate steering output given a turn rate167// desired turn rate in radians/sec. Positive to the right.168void calc_steering_from_turn_rate(float turn_rate);169170// calculate steering angle given a desired lateral acceleration171void calc_steering_from_lateral_acceleration(float lat_accel, bool reversed = false);172173// calculate steering output to drive towards desired heading174// rate_max is a maximum turn rate in deg/s. set to zero to use default turn rate limits175void calc_steering_to_heading(float desired_heading_cd, float rate_max_degs = 0.0f);176177// calculates the amount of throttle that should be output based178// on things like proximity to corners and current speed179virtual void calc_throttle(float target_speed, bool avoidance_enabled);180181// performs a controlled stop. returns true once vehicle has stopped182bool stop_vehicle();183184// estimate maximum vehicle speed (in m/s)185// cruise_speed is in m/s, cruise_throttle should be in the range -1 to +1186float calc_speed_max(float cruise_speed, float cruise_throttle) const;187188// calculate pilot input to nudge speed up or down189// target_speed should be in meters/sec190// 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 down191float calc_speed_nudge(float target_speed, bool reversed);192193protected:194195// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments196// steering_out is in the range -4500 ~ +4500 with positive numbers meaning rotate clockwise197// throttle_out is in the range -100 ~ +100198void get_pilot_input(float &steering_out, float &throttle_out) const;199void set_steering(float steering_value);200201// references to avoid code churn:202class AP_AHRS &ahrs;203class Parameters &g;204class ParametersG2 &g2;205class RC_Channel *&channel_steer;206class RC_Channel *&channel_throttle;207class RC_Channel *&channel_lateral;208class RC_Channel *&channel_roll;209class RC_Channel *&channel_pitch;210class RC_Channel *&channel_walking_height;211class AR_AttitudeControl &attitude_control;212213// private members for waypoint navigation214float _distance_to_destination; // distance from vehicle to final destination in meters215bool _reached_destination; // true once the vehicle has reached the destination216float _desired_yaw_cd; // desired yaw in centi-degrees. used in Auto, Guided and Loiter217};218219220class ModeAcro : public Mode221{222public:223224Number mode_number() const override { return Number::ACRO; }225const char *name4() const override { return "ACRO"; }226227// methods that affect movement of the vehicle in this mode228void update() override;229230// attributes for mavlink system status reporting231bool has_manual_input() const override { return true; }232233// acro mode requires a velocity estimate for non skid-steer rovers234bool requires_position() const override { return false; }235bool requires_velocity() const override;236237// sailboats in acro mode support user manually initiating tacking from transmitter238void handle_tack_request() override;239};240241242class ModeAuto : public Mode243{244public:245246Number mode_number() const override { return Number::AUTO; }247const char *name4() const override { return "AUTO"; }248249// methods that affect movement of the vehicle in this mode250void update() override;251void calc_throttle(float target_speed, bool avoidance_enabled) override;252253// attributes of the mode254bool is_autopilot_mode() const override { return true; }255256// return if external control is allowed in this mode (Guided or Guided-within-Auto)257bool in_guided_mode() const override { return _submode == SubMode::Guided || _submode == SubMode::NavScriptTime; }258259// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)260float wp_bearing() const override;261float nav_bearing() const override;262float crosstrack_error() const override;263float get_desired_lat_accel() const override;264265// return distance (in meters) to destination266float get_distance_to_destination() const override;267268// get or set desired location269bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;270bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED;271bool reached_destination() const override;272273// set desired speed in m/s274bool set_desired_speed(float speed) override;275276// start RTL (within auto)277void start_RTL();278279// lua accessors for nav script time support280bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4);281void nav_script_time_done(uint16_t id);282283//284void init_reversed_flag() override {285if (!mission.is_resume()) {286set_reversed(false);287}288}289290AP_Mission mission{291FUNCTOR_BIND_MEMBER(&ModeAuto::start_command, bool, const AP_Mission::Mission_Command&),292FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&),293FUNCTOR_BIND_MEMBER(&ModeAuto::exit_mission, void)};294295enum class DoneBehaviour : uint8_t {296HOLD = 0,297LOITER = 1,298ACRO = 2,299MANUAL = 3,300};301302protected:303304bool _enter() override;305void _exit() override;306307enum SubMode: uint8_t {308WP, // drive to a given location309HeadingAndSpeed, // turn to a given heading310RTL, // perform RTL within auto mode311Loiter, // perform Loiter within auto mode312Guided, // handover control to external navigation system from within auto mode313Stop, // stop the vehicle as quickly as possible314NavScriptTime, // accept targets from lua scripts while NAV_SCRIPT_TIME commands are executing315Circle, // circle a given location316} _submode;317318private:319320bool check_trigger(void);321bool start_loiter();322void start_guided(const Location& target_loc);323void start_stop();324void send_guided_position_target();325326bool start_command(const AP_Mission::Mission_Command& cmd);327void exit_mission();328bool verify_command_callback(const AP_Mission::Mission_Command& cmd);329330bool verify_command(const AP_Mission::Mission_Command& cmd);331void do_RTL(void);332bool do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination);333void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);334void do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd);335void do_nav_delay(const AP_Mission::Mission_Command& cmd);336bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);337bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);338bool verify_RTL() const;339bool verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd);340bool verify_loiter_time(const AP_Mission::Mission_Command& cmd);341bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);342bool verify_nav_set_yaw_speed();343bool do_circle(const AP_Mission::Mission_Command& cmd);344bool verify_circle(const AP_Mission::Mission_Command& cmd);345void do_wait_delay(const AP_Mission::Mission_Command& cmd);346void do_within_distance(const AP_Mission::Mission_Command& cmd);347bool verify_wait_delay();348bool verify_within_distance();349void do_change_speed(const AP_Mission::Mission_Command& cmd);350void do_set_home(const AP_Mission::Mission_Command& cmd);351void do_set_reverse(const AP_Mission::Mission_Command& cmd);352void do_guided_limits(const AP_Mission::Mission_Command& cmd);353#if AP_SCRIPTING_ENABLED354void do_nav_script_time(const AP_Mission::Mission_Command& cmd);355bool verify_nav_script_time();356#endif357358bool waiting_to_start; // true if waiting for EKF origin before starting mission359bool auto_triggered; // true when auto has been triggered to start360361// HeadingAndSpeed sub mode variables362float _desired_speed; // desired speed in HeadingAndSpeed submode363bool _reached_heading; // true when vehicle has reached desired heading in TurnToHeading sub mode364365// Loiter control366uint16_t loiter_duration; // How long we should loiter at the nav_waypoint (time in seconds)367uint32_t loiter_start_time; // How long have we been loitering - The start time in millis368bool previously_reached_wp; // set to true if we have EVER reached the waypoint369370// Guided-within-Auto variables371struct {372Location loc; // location target sent to external navigation373bool valid; // true if loc is valid374uint32_t last_sent_ms; // system time that target was last sent to offboard navigation375} guided_target;376377// Conditional command378// A value used in condition commands (eg delay, change alt, etc.)379// For example in a change altitude command, it is the altitude to change to.380int32_t condition_value;381// A starting value used to check the status of a conditional command.382// For example in a delay command the condition_start records that start time for the delay383int32_t condition_start;384385// Delay the next navigation command386uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands387uint32_t nav_delay_time_start_ms;388389#if AP_SCRIPTING_ENABLED390// nav_script_time command variables391struct {392bool done; // true once lua script indicates it has completed393uint16_t id; // unique id to avoid race conditions between commands and lua scripts394uint32_t start_ms; // system time nav_script_time command was received (used for timeout)395uint8_t command; // command number provided by mission command396uint8_t timeout_s; // timeout (in seconds) provided by mission command397float arg1; // 1st argument provided by mission command398float arg2; // 2nd argument provided by mission command399int16_t arg3; // 3rd argument provided by mission command400int16_t arg4; // 4th argument provided by mission command401} nav_scripting;402#endif403404// Mission change detector405AP_Mission_ChangeDetector mis_change_detector;406};407408class ModeCircle : public Mode409{410public:411412// need a constructor for parameters413ModeCircle();414415// Does not allow copies416CLASS_NO_COPY(ModeCircle);417418Number mode_number() const override { return Number::CIRCLE; }419const char *name4() const override { return "CIRC"; }420421// initialise with specific center location, radius (in meters) and direction422// replaces use of _enter when initialised from within Auto mode423bool set_center(const Location& center_loc, float radius_m, bool dir_ccw);424425// methods that affect movement of the vehicle in this mode426void update() override;427428bool is_autopilot_mode() const override { return true; }429430// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)431float wp_bearing() const override;432float nav_bearing() const override;433float crosstrack_error() const override { return dist_to_edge_m; }434float get_desired_lat_accel() const override;435436// set desired speed in m/s437bool set_desired_speed(float speed_ms) override;438439// return distance (in meters) to destination440float get_distance_to_destination() const override { return _distance_to_destination; }441442// get or set desired location443bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;444445// return total angle in radians that vehicle has circled446// fabsf is used so that full rotations in either direction are counted447float get_angle_total_rad() const { return fabsf(angle_total_rad); }448449static const struct AP_Param::GroupInfo var_info[];450451protected:452453AP_Float radius; // circle radius in meters454AP_Float speed; // vehicle speed in m/s. If zero uses WP_SPEED455AP_Int8 direction; // direction 0:clockwise, 1:counter-clockwise456457// initialise mode458bool _enter() override;459460// Update position controller targets driving to the circle edge461void update_drive_to_radius();462463// Update position controller targets while circling464void update_circling();465466// initialise target_yaw_rad using the vehicle's position and yaw467// if there is no current position estimate target_yaw_rad is set to vehicle yaw468void init_target_yaw_rad();469470// limit config speed so that lateral acceleration is within limits471// outputs warning to user if speed is reduced472void check_config_speed();473474// ensure config radius is no smaller then vehicle's TURN_RADIUS475// radius is increased if necessary and warning is output to the user476void check_config_radius();477478// enum for Direction parameter479enum class Direction {480CW = 0,481CCW = 1482};483484// local members485struct {486Location center_loc; // circle center as a Location487Vector2f center_pos; // circle center as an offset (in meters) from the EKF origin488float radius; // circle radius489float speed; // desired speed around circle in m/s490Direction dir; // direction, 0:clockwise, 1:counter-clockwise491} config;492struct {493float speed; // vehicle's target speed around circle in m/s494float yaw_rad; // earth-frame angle of tarrget point on the circle495Vector2p pos; // latest position target sent to position controller496Vector2f vel; // latest velocity target sent to position controller497Vector2f accel; // latest accel target sent to position controller498} target;499float angle_total_rad; // total angle in radians that vehicle has circled500bool reached_edge; // true once vehicle has reached edge of circle501float dist_to_edge_m; // distance to edge of circle in meters (equivalent to crosstrack error)502bool tracking_back; // true if the vehicle is trying to track back onto the circle503};504505class ModeGuided : public Mode506{507public:508#if AP_EXTERNAL_CONTROL_ENABLED509friend class AP_ExternalControl_Rover;510#endif511512Number mode_number() const override { return Number::GUIDED; }513const char *name4() const override { return "GUID"; }514515// methods that affect movement of the vehicle in this mode516void update() override;517518// attributes of the mode519bool is_autopilot_mode() const override { return true; }520521// return if external control is allowed in this mode (Guided or Guided-within-Auto)522bool in_guided_mode() const override { return true; }523524// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)525float wp_bearing() const override;526float nav_bearing() const override;527float crosstrack_error() const override;528float get_desired_lat_accel() const override;529530// return distance (in meters) to destination531float get_distance_to_destination() const override;532533// return true if vehicle has reached destination534bool reached_destination() const override;535536// set desired speed in m/s537bool set_desired_speed(float speed) override;538539// get or set desired location540bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;541bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED;542543// set desired heading and speed544void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed);545546// set desired heading-delta, turn-rate and speed547void set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed);548void set_desired_turn_rate_and_speed(float turn_rate_cds, float target_speed);549550// set steering and throttle (-1 to +1). Only called from scripts551void set_steering_and_throttle(float steering, float throttle);552553// vehicle start loiter554bool start_loiter();555556// start stopping557void start_stop();558559// guided limits560void limit_set(uint32_t timeout_ms, float horiz_max);561void limit_clear();562void limit_init_time_and_location();563bool limit_breached() const;564565protected:566567enum class SubMode: uint8_t {568WP,569HeadingAndSpeed,570TurnRateAndSpeed,571Loiter,572SteeringAndThrottle,573Stop574};575576// enum for GUID_OPTIONS parameter577enum class Options : int32_t {578SCurvesUsedForNavigation = (1U << 6)579};580581bool _enter() override;582583// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping584// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping)585bool use_scurves_for_navigation() const;586587SubMode _guided_mode; // stores which GUIDED mode the vehicle is in588589// attitude control590bool have_attitude_target; // true if we have a valid attitude target591uint32_t _des_att_time_ms; // system time last call to set_desired_attitude was made (used for timeout)592float _desired_yaw_rate_cds;// target turn rate centi-degrees per second593bool send_notification; // used to send one time notification to ground station594float _desired_speed; // desired speed used only in HeadingAndSpeed submode595596// direct steering and throttle control597bool _have_strthr; // true if we have a valid direct steering and throttle inputs598uint32_t _strthr_time_ms; // system time last call to set_steering_and_throttle was made (used for timeout)599float _strthr_steering; // direct steering input in the range -1 to +1600float _strthr_throttle; // direct throttle input in the range -1 to +1601602// limits603struct {604uint32_t timeout_ms;// timeout from the time that guided is invoked605float horiz_max; // horizontal position limit in meters from where guided mode was initiated (0 = no limit)606uint32_t start_time_ms; // system time in milliseconds that control was handed to the external computer607Location start_loc; // starting location for checking horiz_max limit608} limit;609};610611612class ModeHold : public Mode613{614public:615616Number mode_number() const override { return Number::HOLD; }617const char *name4() const override { return "HOLD"; }618619// methods that affect movement of the vehicle in this mode620void update() override;621622// attributes for mavlink system status reporting623bool attitude_stabilized() const override { return false; }624625// hold mode does not require position or velocity estimate626bool requires_position() const override { return false; }627bool requires_velocity() const override { return false; }628};629630class ModeLoiter : public Mode631{632public:633634Number mode_number() const override { return Number::LOITER; }635const char *name4() const override { return "LOIT"; }636637// methods that affect movement of the vehicle in this mode638void update() override;639640// attributes of the mode641bool is_autopilot_mode() const override { return true; }642643// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)644float wp_bearing() const override { return _desired_yaw_cd * 0.01f; }645float nav_bearing() const override { return _desired_yaw_cd * 0.01f; }646float crosstrack_error() const override { return 0.0f; }647648// return desired location649bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;650651// return distance (in meters) to destination652float get_distance_to_destination() const override { return _distance_to_destination; }653654protected:655656bool _enter() override;657658Location _destination; // target location to hold position around659float _desired_speed; // desired speed (ramped down from initial speed to zero)660};661662class ModeManual : public Mode663{664public:665666Number mode_number() const override { return Number::MANUAL; }667const char *name4() const override { return "MANU"; }668669// methods that affect movement of the vehicle in this mode670void update() override;671672// attributes for mavlink system status reporting673bool has_manual_input() const override { return true; }674bool attitude_stabilized() const override { return false; }675676// manual mode does not require position or velocity estimate677bool requires_position() const override { return false; }678bool requires_velocity() const override { return false; }679680protected:681682void _exit() override;683};684685686class ModeRTL : public Mode687{688public:689690Number mode_number() const override { return Number::RTL; }691const char *name4() const override { return "RTL"; }692693// methods that affect movement of the vehicle in this mode694void update() override;695696// attributes of the mode697bool is_autopilot_mode() const override { return true; }698699// do not allow arming from this mode700bool allows_arming() const override { return false; }701702// return desired location703bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;704705// return distance (in meters) to destination706float get_distance_to_destination() const override { return _distance_to_destination; }707bool reached_destination() const override;708709// set desired speed in m/s710bool set_desired_speed(float speed) override;711712protected:713714bool _enter() override;715716bool send_notification; // used to send one time notification to ground station717bool _loitering; // true if loitering at end of RTL718719};720721class ModeSmartRTL : public Mode722{723public:724725Number mode_number() const override { return Number::SMART_RTL; }726const char *name4() const override { return "SRTL"; }727728// methods that affect movement of the vehicle in this mode729void update() override;730731// attributes of the mode732bool is_autopilot_mode() const override { return true; }733734// do not allow arming from this mode735bool allows_arming() const override { return false; }736737// return desired location738bool get_desired_location(Location& destination) const override WARN_IF_UNUSED;739740// return distance (in meters) to destination741float get_distance_to_destination() const override { return _distance_to_destination; }742bool reached_destination() const override { return smart_rtl_state == SmartRTLState::StopAtHome; }743744// set desired speed in m/s745bool set_desired_speed(float speed) override;746747// save current position for use by the smart_rtl flight mode748void save_position();749750protected:751752// Safe RTL states753enum class SmartRTLState: uint8_t {754WaitForPathCleanup,755PathFollow,756StopAtHome,757Failure758} smart_rtl_state;759760bool _enter() override;761bool _load_point;762bool _loitering; // true if loitering at end of SRTL763};764765766767class ModeSteering : public Mode768{769public:770771Number mode_number() const override { return Number::STEERING; }772const char *name4() const override { return "STER"; }773774// methods that affect movement of the vehicle in this mode775void update() override;776777// attributes for mavlink system status reporting778bool has_manual_input() const override { return true; }779780// steering requires velocity but not position781bool requires_position() const override { return false; }782bool requires_velocity() const override { return true; }783784// return desired lateral acceleration785float get_desired_lat_accel() const override { return _desired_lat_accel; }786787private:788789float _desired_lat_accel; // desired lateral acceleration calculated from pilot steering input790};791792class ModeInitializing : public Mode793{794public:795796Number mode_number() const override { return Number::INITIALISING; }797const char *name4() const override { return "INIT"; }798799// methods that affect movement of the vehicle in this mode800void update() override { }801802// do not allow arming from this mode803bool allows_arming() const override { return false; }804805// attributes for mavlink system status reporting806bool has_manual_input() const override { return true; }807bool attitude_stabilized() const override { return false; }808protected:809bool _enter() override { return false; };810};811812#if MODE_FOLLOW_ENABLED813class ModeFollow : public Mode814{815public:816817Number mode_number() const override { return Number::FOLLOW; }818const char *name4() const override { return "FOLL"; }819820// methods that affect movement of the vehicle in this mode821void update() override;822823// attributes of the mode824bool is_autopilot_mode() const override { return true; }825826// return desired heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)827float wp_bearing() const override;828float nav_bearing() const override { return wp_bearing(); }829float crosstrack_error() const override { return 0.0f; }830831// return desired location832bool get_desired_location(Location& destination) const override WARN_IF_UNUSED { return false; }833834// return distance (in meters) to destination835float get_distance_to_destination() const override;836837// set desired speed in m/s838bool set_desired_speed(float speed) override;839840protected:841842bool _enter() override;843void _exit() override;844845float _desired_speed; // desired speed in m/s846};847#endif848849class ModeSimple : public Mode850{851public:852853Number mode_number() const override { return Number::SIMPLE; }854const char *name4() const override { return "SMPL"; }855856// methods that affect movement of the vehicle in this mode857void update() override;858void init_heading();859860// simple type enum used for SIMPLE_TYPE parameter861enum simple_type {862Simple_InitialHeading = 0,863Simple_CardinalDirections = 1,864};865866private:867868float _initial_heading_cd; // vehicle heading (in centi-degrees) at moment vehicle was armed869float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot870};871872#if MODE_DOCK_ENABLED873class ModeDock : public Mode874{875public:876877// need a constructor for parameters878ModeDock(void);879880// Does not allow copies881CLASS_NO_COPY(ModeDock);882883Number mode_number() const override { return Number::DOCK; }884const char *name4() const override { return "DOCK"; }885886// methods that affect movement of the vehicle in this mode887void update() override;888889bool is_autopilot_mode() const override { return true; }890891// return distance (in meters) to destination892float get_distance_to_destination() const override { return _distance_to_destination; }893894static const struct AP_Param::GroupInfo var_info[];895896protected:897898AP_Float speed; // dock mode speed899AP_Float desired_dir; // desired direction of approach900AP_Int8 hdg_corr_enable; // enable heading correction901AP_Float hdg_corr_weight; // heading correction weight902AP_Float stopping_dist; // how far away from the docking target should we start stopping903904bool _enter() override;905906// return reduced speed of vehicle based on error in position and current distance from the dock907float apply_slowdown(float desired_speed);908909// calculate position of dock relative to the vehicle910bool calc_dock_pos_rel_vehicle_NE(Vector2f &dock_pos_rel_vehicle) const;911912// we force the vehicle to use real dock target vector when this much close to the docking station913const float _force_real_target_limit_cm = 300.0f;914// acceptable lateral error in vehicle's position with respect to dock. This is used while slowing down the vehicle915const float _acceptable_pos_error_cm = 20.0f;916917Vector2f _dock_pos_rel_origin_cm; // position vector towards docking target relative to ekf origin918Vector2f _desired_heading_NE; // unit vector in desired direction of docking919bool _docking_complete = false; // flag to mark docking complete when we are close enough to the dock920bool _loitering = false; // true if we are loitering after mission completion921};922#endif923924925