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/ArduSub/Sub.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#pragma once15/*16This is the main Sub class17*/1819////////////////////////////////////////////////////////////////////////////////20// Header includes21////////////////////////////////////////////////////////////////////////////////2223#include <cmath>24#include <stdio.h>25#include <stdarg.h>2627#include <AP_HAL/AP_HAL.h>2829// Common dependencies30#include <AP_Common/AP_Common.h>31#include <AP_Common/Location.h>32#include <AP_Param/AP_Param.h>33#include <StorageManager/StorageManager.h>34#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration35#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library36#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library3738// Application dependencies39#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library40#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library41#include <AP_Baro/AP_Baro.h>42#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library43#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library44#include <AP_AHRS/AP_AHRS.h>45#include <AP_Mission/AP_Mission.h> // Mission command library46#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library47#include <AC_AttitudeControl/AC_PosControl.h> // Position control library48#include <AP_Motors/AP_Motors.h> // AP Motors library49#include <Filter/Filter.h> // Filter library50#include <AP_Relay/AP_Relay.h> // APM relay51#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount52#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build53#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library54#include <AC_WPNav/AC_WPNav.h> // Waypoint navigation library55#include <AC_WPNav/AC_Loiter.h>56#include <AC_WPNav/AC_Circle.h> // circle navigation library57#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler58#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring59#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library60#include <AP_Terrain/AP_Terrain.h>61#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment62#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector63#include <AP_Proximity/AP_Proximity.h>64#include <AP_Rally/AP_Rally.h>6566// Local modules67#include "defines.h"68#include "config.h"69#include "GCS_MAVLink_Sub.h"70#include "RC_Channel_Sub.h" // RC Channel Library71#include "Parameters.h"72#include "AP_Arming_Sub.h"73#include "GCS_Sub.h"74#include "mode.h"75#include "script_button.h"7677#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library7879// libraries which are dependent on #defines in defines.h and/or config.h80#if RCMAP_ENABLED81#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library82#endif8384#include <AP_RPM/AP_RPM_config.h>8586#if AP_RPM_ENABLED87#include <AP_RPM/AP_RPM.h>88#endif8990#if AVOIDANCE_ENABLED91#include <AC_Avoidance/AC_Avoid.h> // Stop at fence library92#endif9394#include <AP_Camera/AP_Camera.h> // Photo or video camera9596#if AP_SCRIPTING_ENABLED97#include <AP_Scripting/AP_Scripting.h>98#endif99100class Sub : public AP_Vehicle {101public:102friend class GCS_MAVLINK_Sub;103friend class GCS_Sub;104friend class Parameters;105friend class ParametersG2;106friend class AP_Arming_Sub;107friend class RC_Channels_Sub;108friend class Mode;109friend class ModeManual;110friend class ModeStabilize;111friend class ModeAcro;112friend class ModeAlthold;113friend class ModeSurftrak;114friend class ModeGuided;115friend class ModePoshold;116friend class ModeAuto;117friend class ModeCircle;118friend class ModeSurface;119friend class ModeMotordetect;120121Sub(void);122123protected:124125bool should_zero_rc_outputs_on_reboot() const override { return true; }126127private:128129// key aircraft parameters passed to multiple libraries130AP_MultiCopter aparm;131132// Global parameters are all contained within the 'g' class.133Parameters g;134ParametersG2 g2;135136// primary input control channels137RC_Channel *channel_roll;138RC_Channel *channel_pitch;139RC_Channel *channel_throttle;140RC_Channel *channel_yaw;141RC_Channel *channel_forward;142RC_Channel *channel_lateral;143144AP_LeakDetector leak_detector;145146struct {147bool enabled:1;148bool alt_healthy:1; // true if we can trust the altitude from the rangefinder149int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder150int16_t min_cm; // min rangefinder distance (in cm)151int16_t max_cm; // max rangefinder distance (in cm)152uint32_t last_healthy_ms;153float inertial_alt_cm; // inertial alt at time of last rangefinder sample154float rangefinder_terrain_offset_cm; // terrain height above EKF origin155LowPassFilterFloat alt_cm_filt; // altitude filter156} rangefinder_state = { false, false, 0, 0, 0, 0, 0, 0 };157158#if AP_RPM_ENABLED159AP_RPM rpm_sensor;160#endif161162// Mission library163AP_Mission mission{164FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),165FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),166FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)};167168// Optical flow sensor169#if AP_OPTICALFLOW_ENABLED170AP_OpticalFlow optflow;171#endif172173// system time in milliseconds of last recorded yaw reset from ekf174uint32_t ekfYawReset_ms = 0;175176// GCS selection177GCS_Sub _gcs; // avoid using this; use gcs()178GCS_Sub &gcs() { return _gcs; }179180// User variables181#ifdef USERHOOK_VARIABLES182# include USERHOOK_VARIABLES183#endif184185// Documentation of Globals:186union {187struct {188uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed189uint8_t logging_started : 1; // true if logging has started190uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration191uint8_t motor_test : 1; // true if we are currently performing the motors test192uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes193uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)194uint8_t at_bottom : 1; // true if we are at the bottom195uint8_t at_surface : 1; // true if we are at the surface196uint8_t depth_sensor_present: 1; // true if there is a depth sensor detected at boot197uint8_t unused1 : 1; // was compass_init_location; true when the compass's initial location has been set198};199uint32_t value;200} ap;201202// This is the state of the flight control system203// There are multiple states defined such as STABILIZE, ACRO,204Mode::Number control_mode;205206Mode::Number prev_control_mode;207208#if RCMAP_ENABLED209RCMapper rcmap;210#endif211212// Failsafe213struct {214uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs215uint32_t last_gcs_warn_ms;216uint32_t last_pilot_input_ms; // last time we received pilot input in the form of MANUAL_CONTROL or RC_CHANNELS_OVERRIDE messages217uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure218uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed219uint32_t last_crash_warn_ms; // last time a crash warning was sent to gcs220uint32_t last_ekf_warn_ms; // last time an ekf warning was sent to gcs221222uint8_t pilot_input : 1; // true if pilot input failsafe is active, handles things like joystick being disconnected during operation223uint8_t gcs : 1; // A status flag for the ground station failsafe224uint8_t ekf : 1; // true if ekf failsafe has occurred225uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred226uint8_t leak : 1; // true if leak recently detected227uint8_t internal_pressure : 1; // true if internal pressure is over threshold228uint8_t internal_temperature : 1; // true if temperature is over threshold229uint8_t crash : 1; // true if we are crashed230uint8_t sensor_health : 1; // true if at least one sensor has triggered a failsafe (currently only used for depth in depth enabled modes)231} failsafe;232233bool any_failsafe_triggered() const {234return (235failsafe.pilot_input236|| battery.has_failsafed()237|| failsafe.gcs238|| failsafe.ekf239|| failsafe.terrain240|| failsafe.leak241|| failsafe.internal_pressure242|| failsafe.internal_temperature243|| failsafe.crash244|| failsafe.sensor_health245);246}247248// sensor health for logging249struct {250uint8_t depth : 1; // true if depth sensor is healthy251uint8_t compass : 1; // true if compass is healthy252} sensor_health;253254// Baro sensor instance index of the external water pressure sensor255uint8_t depth_sensor_idx;256257AP_Motors6DOF motors;258259// Circle260bool circle_pilot_yaw_override; // true if pilot is overriding yaw261262// Stores initial bearing when armed263int32_t initial_armed_bearing;264265// Throttle variables266int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only267268// Loiter control269uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)270uint32_t loiter_time; // How long have we been loitering - The start time in millis271272// Delay the next navigation command273uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands274uint32_t nav_delay_time_start_ms;275276// Battery Sensors277AP_BattMonitor battery{MASK_LOG_CURRENT,278FUNCTOR_BIND_MEMBER(&Sub::handle_battery_failsafe, void, const char*, const int8_t),279_failsafe_priorities};280281AP_Arming_Sub arming;282283// Altitude284// The cm/s we are moving up or down based on filtered data - Positive = UP285int16_t climb_rate;286287// Turn counter288int32_t quarter_turn_count;289uint8_t last_turn_state;290291// Input gain292float gain;293294// Flag indicating if we are currently using input hold295bool input_hold_engaged;296297// Flag indicating if we are currently controlling Pitch and Roll instead of forward/lateral298bool roll_pitch_flag = false;299300// 3D Location vectors301// Current location of the Sub (altitude is relative to home)302Location current_loc;303304// Navigation Yaw control305// auto flight mode's yaw mode306uint8_t auto_yaw_mode;307308// Parameter to set yaw rate only309bool yaw_rate_only;310311// Yaw will point at this location if auto_yaw_mode is set to AUTO_YAW_ROI312Vector3f roi_WP;313314// bearing from current location to the yaw_look_at_WP315float yaw_look_at_WP_bearing;316317float yaw_xtrack_correct_heading;318319// yaw used for YAW_LOOK_AT_HEADING yaw_mode320int32_t yaw_look_at_heading;321322// Deg/s we should turn323int16_t yaw_look_at_heading_slew;324325// heading when in yaw_look_ahead_bearing326float yaw_look_ahead_bearing;327328// Delay Mission Scripting Command329int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)330uint32_t condition_start;331332// Inertial Navigation333AP_InertialNav inertial_nav;334335AP_AHRS_View ahrs_view;336337// Attitude, Position and Waypoint navigation objects338// To-Do: move inertial nav up or other navigation variables down here339AC_AttitudeControl_Sub attitude_control;340341AC_PosControl pos_control;342343AC_WPNav wp_nav;344AC_Loiter loiter_nav;345AC_Circle circle_nav;346347// Camera348#if AP_CAMERA_ENABLED349AP_Camera camera{MASK_LOG_CAMERA};350#endif351352// Camera/Antenna mount tracking and stabilisation stuff353#if HAL_MOUNT_ENABLED354AP_Mount camera_mount;355#endif356357#if AVOIDANCE_ENABLED358AC_Avoid avoid;359#endif360361// Rally library362#if HAL_RALLY_ENABLED363AP_Rally rally;364#endif365366// terrain handling367#if AP_TERRAIN_AVAILABLE368AP_Terrain terrain;369#endif370371// used to allow attitude and depth control without a position system372struct attitude_no_gps_struct {373uint32_t last_message_ms;374mavlink_set_attitude_target_t packet;375};376377attitude_no_gps_struct set_attitude_target_no_gps {0};378379// Top-level logic380// setup the var_info table381AP_Param param_loader;382383uint32_t last_pilot_heading;384uint32_t last_pilot_yaw_input_ms;385uint32_t fs_terrain_recover_start_ms;386387static const AP_Scheduler::Task scheduler_tasks[];388static const AP_Param::Info var_info[];389static const struct LogStructure log_structure[];390391void run_rate_controller();392void fifty_hz_loop();393void update_batt_compass(void);394void ten_hz_logging_loop();395void twentyfive_hz_logging();396void three_hz_loop();397void one_hz_loop();398void update_turn_counter();399void read_AHRS(void);400void update_altitude();401float get_smoothing_gain();402void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);403float get_pilot_desired_yaw_rate(int16_t stick_angle) const;404void check_ekf_yaw_reset();405float get_roi_yaw();406float get_look_ahead_yaw();407float get_pilot_desired_climb_rate(float throttle_control);408void rotate_body_frame_to_NE(float &x, float &y);409#if HAL_LOGGING_ENABLED410// methods for AP_Vehicle:411const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }412const struct LogStructure *get_log_structures() const override {413return log_structure;414}415uint8_t get_num_log_structures() const override;416417void Log_Write_Control_Tuning();418void Log_Write_Attitude();419void Log_Write_Data(LogDataID id, int32_t value);420void Log_Write_Data(LogDataID id, uint32_t value);421void Log_Write_Data(LogDataID id, int16_t value);422void Log_Write_Data(LogDataID id, uint16_t value);423void Log_Write_Data(LogDataID id, float value);424void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);425void Log_Write_Vehicle_Startup_Messages();426#endif427void load_parameters(void) override;428void userhook_init();429void userhook_FastLoop();430void userhook_50Hz();431void userhook_MediumLoop();432void userhook_SlowLoop();433void userhook_SuperSlowLoop();434void update_home_from_EKF();435void set_home_to_current_location_inflight();436bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;437bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;438float get_alt_rel() const WARN_IF_UNUSED;439float get_alt_msl() const WARN_IF_UNUSED;440void exit_mission();441void set_origin(const Location& loc);442bool ensure_ekf_origin();443bool verify_loiter_unlimited();444bool verify_loiter_time();445bool verify_wait_delay();446bool verify_within_distance();447bool verify_yaw();448449void failsafe_sensors_check(void);450void failsafe_crash_check();451void failsafe_ekf_check(void);452void handle_battery_failsafe(const char* type_str, const int8_t action);453void failsafe_gcs_check();454void failsafe_pilot_input_check(void);455void set_neutral_controls(void);456void failsafe_terrain_check();457void failsafe_terrain_set_status(bool data_ok);458void failsafe_terrain_on_event();459void mainloop_failsafe_enable();460void mainloop_failsafe_disable();461void fence_check();462bool set_mode(Mode::Number mode, ModeReason reason);463bool set_mode(const uint8_t new_mode, const ModeReason reason) override;464uint8_t get_mode() const override { return (uint8_t)control_mode; }465void update_flight_mode();466void exit_mode(Mode::Number old_control_mode, Mode::Number new_control_mode);467void notify_flight_mode();468void read_inertia();469void update_surface_and_bottom_detector();470void set_surfaced(bool at_surface);471void set_bottomed(bool at_bottom);472void motors_output();473void init_rc_in();474void init_rc_out();475void enable_motor_output();476void init_joystick();477void transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions,478int16_t s,479int16_t t,480int16_t aux1,481int16_t aux2,482int16_t aux3,483int16_t aux4,484int16_t aux5,485int16_t aux6);486void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);487void handle_jsbutton_release(uint8_t button, bool shift);488JSButton* get_button(uint8_t index);489void default_js_buttons(void);490void clear_input_hold();491void read_barometer(void);492void init_rangefinder(void);493void read_rangefinder(void);494void terrain_update();495void terrain_logging();496void init_ardupilot() override;497void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,498uint8_t &task_count,499uint32_t &log_bit) override;500void startup_INS_ground();501bool position_ok();502bool ekf_position_ok();503bool optflow_position_ok();504bool should_log(uint32_t mask);505bool start_command(const AP_Mission::Mission_Command& cmd);506bool verify_command(const AP_Mission::Mission_Command& cmd);507bool verify_command_callback(const AP_Mission::Mission_Command& cmd);508509bool do_guided(const AP_Mission::Mission_Command& cmd);510void do_nav_wp(const AP_Mission::Mission_Command& cmd);511void do_surface(const AP_Mission::Mission_Command& cmd);512void do_RTL(void);513void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd);514void do_circle(const AP_Mission::Mission_Command& cmd);515void do_loiter_time(const AP_Mission::Mission_Command& cmd);516#if NAV_GUIDED517void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);518void do_guided_limits(const AP_Mission::Mission_Command& cmd);519#endif520void do_nav_delay(const AP_Mission::Mission_Command& cmd);521void do_wait_delay(const AP_Mission::Mission_Command& cmd);522void do_within_distance(const AP_Mission::Mission_Command& cmd);523void do_yaw(const AP_Mission::Mission_Command& cmd);524void do_change_speed(const AP_Mission::Mission_Command& cmd);525void do_set_home(const AP_Mission::Mission_Command& cmd);526void do_roi(const AP_Mission::Mission_Command& cmd);527void do_mount_control(const AP_Mission::Mission_Command& cmd);528529bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);530bool verify_surface(const AP_Mission::Mission_Command& cmd);531bool verify_RTL(void);532bool verify_circle(const AP_Mission::Mission_Command& cmd);533#if NAV_GUIDED534bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);535#endif536bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);537538void failsafe_leak_check();539void failsafe_internal_pressure_check();540void failsafe_internal_temperature_check();541542void failsafe_terrain_act(void);543544545void translate_wpnav_rp(float &lateral_out, float &forward_out);546void translate_circle_nav_rp(float &lateral_out, float &forward_out);547void translate_pos_control_rp(float &lateral_out, float &forward_out);548549void stats_update();550551uint16_t get_pilot_speed_dn() const;552553void convert_old_parameters(void);554bool handle_do_motor_test(mavlink_command_int_t command);555bool init_motor_test();556bool verify_motor_test();557558uint32_t last_do_motor_test_fail_ms = 0;559uint32_t last_do_motor_test_ms = 0;560561bool control_check_barometer();562563// vehicle specific waypoint info helpers564bool get_wp_distance_m(float &distance) const override;565bool get_wp_bearing_deg(float &bearing) const override;566bool get_wp_crosstrack_error_m(float &xtrack_error) const override;567568enum Failsafe_Action {569Failsafe_Action_None = 0,570Failsafe_Action_Warn = 1,571Failsafe_Action_Disarm = 2,572Failsafe_Action_Surface = 3573};574575static constexpr int8_t _failsafe_priorities[] = {576Failsafe_Action_Disarm,577Failsafe_Action_Surface,578Failsafe_Action_Warn,579Failsafe_Action_None,580-1 // the priority list must end with a sentinel of -1581};582583static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,584"_failsafe_priorities is missing the sentinel");585586Mode *mode_from_mode_num(const Mode::Number num);587void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);588589Mode *flightmode;590ModeManual mode_manual;591ModeStabilize mode_stabilize;592ModeAcro mode_acro;593ModeAlthold mode_althold;594ModeAuto mode_auto;595ModeGuided mode_guided;596ModePoshold mode_poshold;597ModeCircle mode_circle;598ModeSurface mode_surface;599ModeMotordetect mode_motordetect;600ModeSurftrak mode_surftrak;601602// Auto603AutoSubMode auto_mode; // controls which auto controller is run604GuidedSubMode guided_mode;605606#if AP_SCRIPTING_ENABLED607ScriptButton script_buttons[4];608#endif // AP_SCRIPTING_ENABLED609610public:611void mainloop_failsafe_check();612bool rangefinder_alt_ok() const WARN_IF_UNUSED;613614static Sub *_singleton;615616static Sub *get_singleton() {617return _singleton;618}619620#if AP_SCRIPTING_ENABLED621// For Lua scripting, so index is 1..4, not 0..3622bool is_button_pressed(uint8_t index);623624// For Lua scripting, so index is 1..4, not 0..3625uint8_t get_and_clear_button_count(uint8_t index);626627#if AP_RANGEFINDER_ENABLED628float get_rangefinder_target_cm() const WARN_IF_UNUSED { return mode_surftrak.get_rangefinder_target_cm(); }629bool set_rangefinder_target_cm(float new_target_cm) { return mode_surftrak.set_rangefinder_target_cm(new_target_cm); }630#endif // AP_RANGEFINDER_ENABLED631#endif // AP_SCRIPTING_ENABLED632};633634extern const AP_HAL::HAL& hal;635extern Sub sub;636637638