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/Blimp/mode.h
Views: 1798
#pragma once12#include "Blimp.h"3class Parameters;4class ParametersG2;56class GCS_Blimp;78class Mode9{1011public:1213// Auto Pilot Modes enumeration14enum class Number : uint8_t {15LAND = 0, // currently just stops moving16MANUAL = 1, // manual control17VELOCITY = 2, // velocity mode18LOITER = 3, // loiter mode (position hold)19RTL = 4, // rtl20// Mode number 30 reserved for "offboard" for external/lua control.21};2223// constructor24Mode(void);2526// do not allow copying27CLASS_NO_COPY(Mode);2829// child classes should override these methods30virtual bool init(bool ignore_checks)31{32return true;33}34virtual void run() = 0;35virtual bool requires_GPS() const = 0;36virtual bool has_manual_throttle() const = 0;37virtual bool allows_arming(bool from_gcs) const = 0;38virtual bool is_autopilot() const39{40return false;41}42virtual bool has_user_takeoff(bool must_navigate) const43{44return false;45}46virtual bool in_guided_mode() const47{48return false;49}5051// return a string for this flightmode52virtual const char *name() const = 0;53virtual const char *name4() const = 0;5455// returns a unique number specific to this mode56virtual Mode::Number number() const = 0;5758virtual bool is_landing() const59{60return false;61}6263// mode requires terrain to be present to be functional64virtual bool requires_terrain_failsafe() const65{66return false;67}6869// functions for reporting to GCS70virtual bool get_wp(Location &loc)71{72return false;73};74virtual int32_t wp_bearing() const75{76return 0;77}78virtual uint32_t wp_distance() const79{80return 0;81}82virtual float crosstrack_error() const83{84return 0.0f;85}8687void update_navigation();8889// pilot input processing90void get_pilot_input(Vector3f &pilot, float &yaw);9192protected:9394// navigation support functions95virtual void run_autopilot() {}9697// helper functions98bool is_disarmed_or_landed() const;99100// functions to control landing101// in modes that support landing102void land_run_horizontal_control();103void land_run_vertical_control(bool pause_descent = false);104105// convenience references to avoid code churn in conversion:106Parameters &g;107ParametersG2 &g2;108AP_InertialNav &inertial_nav;109AP_AHRS &ahrs;110Fins *&motors;111Loiter *&loiter;112RC_Channel *&channel_right;113RC_Channel *&channel_front;114RC_Channel *&channel_up;115RC_Channel *&channel_yaw;116float &G_Dt;117118public:119// pass-through functions to reduce code churn on conversion;120// these are candidates for moving into the Mode base121// class.122bool set_mode(Mode::Number mode, ModeReason reason);123GCS_Blimp &gcs();124125// end pass-through functions126};127128class ModeManual : public Mode129{130131public:132// inherit constructor133using Mode::Mode;134135virtual void run() override;136137bool requires_GPS() const override138{139return false;140}141bool has_manual_throttle() const override142{143return true;144}145bool allows_arming(bool from_gcs) const override146{147return true;148};149bool is_autopilot() const override150{151return false;152}153154protected:155156const char *name() const override157{158return "MANUAL";159}160const char *name4() const override161{162return "MANU";163}164165Mode::Number number() const override { return Mode::Number::MANUAL; }166167private:168169};170171class ModeVelocity : public Mode172{173174public:175// inherit constructor176using Mode::Mode;177178virtual void run() override;179180bool requires_GPS() const override181{182return true;183}184bool has_manual_throttle() const override185{186return false;187}188bool allows_arming(bool from_gcs) const override189{190return true;191};192bool is_autopilot() const override193{194return false;195//TODO196}197198protected:199200const char *name() const override201{202return "VELOCITY";203}204const char *name4() const override205{206return "VELY";207}208209Mode::Number number() const override { return Mode::Number::VELOCITY; }210211private:212213};214215class ModeLoiter : public Mode216{217218public:219// inherit constructor220using Mode::Mode;221222virtual bool init(bool ignore_checks) override;223virtual void run() override;224225bool requires_GPS() const override226{227return true;228}229bool has_manual_throttle() const override230{231return false;232}233bool allows_arming(bool from_gcs) const override234{235return true;236};237bool is_autopilot() const override238{239return false;240//TODO241}242243protected:244245const char *name() const override246{247return "LOITER";248}249const char *name4() const override250{251return "LOIT";252}253254Mode::Number number() const override { return Mode::Number::LOITER; }255256private:257Vector3f target_pos;258float target_yaw;259};260261class ModeLand : public Mode262{263264public:265// inherit constructor266using Mode::Mode;267268virtual void run() override;269270bool requires_GPS() const override271{272return false;273}274bool has_manual_throttle() const override275{276return true;277}278bool allows_arming(bool from_gcs) const override279{280return false;281};282bool is_autopilot() const override283{284return false;285}286287protected:288289const char *name() const override290{291return "LAND";292}293const char *name4() const override294{295return "LAND";296}297298Mode::Number number() const override { return Mode::Number::LAND; }299300private:301302};303304class ModeRTL : public Mode305{306307public:308// inherit constructor309using Mode::Mode;310311virtual bool init(bool ignore_checks) override;312virtual void run() override;313314bool requires_GPS() const override315{316return true;317}318bool has_manual_throttle() const override319{320return false;321}322bool allows_arming(bool from_gcs) const override323{324return true;325};326bool is_autopilot() const override327{328return false;329//TODO330}331332protected:333334const char *name() const override335{336return "RTL";337}338const char *name4() const override339{340return "RTL";341}342343Mode::Number number() const override { return Mode::Number::RTL; }344345};346347348