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/Blimp.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 Blimp 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>3435// Application dependencies36#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library37#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library38// #include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration39// #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library40#include <AP_AHRS/AP_AHRS.h>41#include <Filter/Filter.h> // Filter library42#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build43#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library44#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library45#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library46#include <AP_Arming/AP_Arming.h>47#include <AP_Scripting/AP_Scripting.h>48#include <AC_PID/AC_PID_2D.h>49#include <AC_PID/AC_PID_Basic.h>50#include <AC_PID/AC_PID.h>51#include <AP_Vehicle/AP_MultiCopter.h>5253#include <Filter/NotchFilter.h>5455// Configuration56#include "defines.h"57#include "config.h"5859#include "Fins.h"60#include "Loiter.h"6162#include "RC_Channel_Blimp.h" // RC Channel Library6364#include "GCS_MAVLink_Blimp.h"65#include "GCS_Blimp.h"66#include "AP_Arming.h"6768#include <AP_Mount/AP_Mount.h>6970// Local modules7172#include "Parameters.h"7374#include "mode.h"7576class Blimp : public AP_Vehicle77{78public:79friend class GCS_MAVLINK_Blimp;80friend class GCS_Blimp;81friend class Parameters;82friend class ParametersG2;8384friend class AP_Arming_Blimp;85friend class RC_Channel_Blimp;86friend class RC_Channels_Blimp;8788friend class Mode;89friend class ModeManual;90friend class ModeLand;91friend class ModeVelocity;92friend class ModeLoiter;93friend class ModeRTL;9495friend class Fins;96friend class Loiter;9798Blimp(void);99100private:101102// key aircraft parameters passed to multiple libraries103AP_MultiCopter aparm;104105// Global parameters are all contained within the 'g' class.106Parameters g;107ParametersG2 g2;108109// primary input control channels110RC_Channel *channel_right;111RC_Channel *channel_front;112RC_Channel *channel_up;113RC_Channel *channel_yaw;114115// flight modes convenience array116AP_Int8 *flight_modes;117const uint8_t num_flight_modes = 6;118119// Arming/Disarming management class120AP_Arming_Blimp arming;121122// system time in milliseconds of last recorded yaw reset from ekf123uint32_t ekfYawReset_ms;124int8_t ekf_primary_core;125126// vibration check127struct {128bool high_vibes; // true while high vibration are detected129uint32_t start_ms; // system time high vibration were last detected130uint32_t clear_ms; // system time high vibrations stopped131} vibration_check;132133// GCS selection134GCS_Blimp _gcs; // avoid using this; use gcs()135GCS_Blimp &gcs()136{137return _gcs;138}139140// Documentation of Globals:141typedef union {142struct {143uint8_t pre_arm_rc_check : 1; // 1 // true if rc input pre-arm checks have been completed successfully144uint8_t pre_arm_check : 1; // 2 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed145uint8_t auto_armed : 1; // 3 // stops auto missions from beginning until throttle is raised146uint8_t logging_started : 1; // 4 // true if logging has started147uint8_t land_complete : 1; // 5 // true if we have detected a landing148uint8_t new_radio_frame : 1; // 6 // Set true if we have new PWM data to act on from the Radio149uint8_t rc_receiver_present_unused : 1; // 7 // UNUSED150uint8_t compass_mot : 1; // 8 // true if we are currently performing compassmot calibration151uint8_t motor_test : 1; // 9 // true if we are currently performing the motors test152uint8_t initialised : 1; // 10 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes153uint8_t land_complete_maybe : 1; // 11 // true if we may have landed (less strict version of land_complete)154uint8_t throttle_zero : 1; // 12 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down155uint8_t gps_glitching : 1; // 13 // true if GPS glitching is affecting navigation accuracy156uint8_t in_arming_delay : 1; // 14 // true while we are armed but waiting to spin motors157uint8_t initialised_params : 1; // 15 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done158};159uint32_t value;160} ap_t;161162ap_t ap;163164static_assert(sizeof(uint32_t) == sizeof(ap), "ap_t must be uint32_t");165166// This is the state of the flight control system167// There are multiple states defined such as STABILIZE, ACRO,168Mode::Number control_mode;169ModeReason control_mode_reason = ModeReason::UNKNOWN;170171RCMapper rcmap;172173// inertial nav alt when we armed174float arming_altitude_m;175176// Failsafe177struct {178int8_t radio_counter; // number of iterations with throttle below throttle_fs_value179180uint8_t radio : 1; // A status flag for the radio failsafe181uint8_t gcs : 1; // A status flag for the ground station failsafe182uint8_t ekf : 1; // true if ekf failsafe has occurred183} failsafe;184185bool any_failsafe_triggered() const186{187return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf;188}189190// Motor Output191Fins *motors;192Loiter *loiter;193194int32_t _home_bearing;195uint32_t _home_distance;196197// Stores initial bearing when armed - initial simple bearing is modified in super simple mode so not suitable198int32_t initial_armed_bearing;199200// Battery Sensors201AP_BattMonitor battery{MASK_LOG_CURRENT,202FUNCTOR_BIND_MEMBER(&Blimp::handle_battery_failsafe, void, const char*, const int8_t),203_failsafe_priorities};204205// Altitude206int32_t baro_alt; // barometer altitude in cm above home207208// filtered pilot's throttle input used to cancel landing if throttle held high209LowPassFilterFloat rc_throttle_control_in_filter;210211// 3D Location vectors212// Current location of the vehicle (altitude is relative to home)213Location current_loc;214Vector3f vel_ned;215Vector3f vel_ned_filtd;216217Vector3f pos_ned;218float vel_yaw;219float vel_yaw_filtd;220NotchFilterVector2f vel_xy_filter;221NotchFilterFloat vel_z_filter;222NotchFilterFloat vel_yaw_filter;223224// Inertial Navigation225AP_InertialNav inertial_nav;226227// Vel & pos PIDs228AC_PID_2D pid_vel_xy{3, 0.2, 0, 0, 0.2, 3, 3}; //These are the defaults - P I D FF IMAX FiltHz FiltDHz DT229AC_PID_Basic pid_vel_z{7, 1.5, 0, 0, 1, 3, 3};230AC_PID_Basic pid_vel_yaw{3, 0.4, 0, 0, 0.2, 3, 3};231232AC_PID_2D pid_pos_xy{1, 0.05, 0, 0, 0.1, 3, 3};233AC_PID_Basic pid_pos_z{0.7, 0, 0, 0, 0, 3, 3};234AC_PID pid_pos_yaw{1.2, 0.5, 0, 0, 2, 3, 3, 3}; //p, i, d, ff, imax, filt_t, filt_e, filt_d, dt, opt srmax, opt srtau235236// System Timers237// --------------238// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.239uint32_t arm_time_ms;240241// Used to exit the roll and pitch auto trim function242uint8_t auto_trim_counter;243bool auto_trim_started = false;244245// last valid RC input time246uint32_t last_radio_update_ms;247248// Top-level logic249// setup the var_info table250AP_Param param_loader;251252bool standby_active;253254static const AP_Scheduler::Task scheduler_tasks[];255static const AP_Param::Info var_info[];256static const struct LogStructure log_structure[];257258enum Failsafe_Action {259Failsafe_Action_None = 0,260Failsafe_Action_Land = 1,261Failsafe_Action_Terminate = 5262};263264enum class FailsafeOption {265RC_CONTINUE_IF_AUTO = (1<<0), // 1266GCS_CONTINUE_IF_AUTO = (1<<1), // 2267RC_CONTINUE_IF_GUIDED = (1<<2), // 4268CONTINUE_IF_LANDING = (1<<3), // 8269GCS_CONTINUE_IF_PILOT_CONTROL = (1<<4), // 16270RELEASE_GRIPPER = (1<<5), // 32271};272273static constexpr int8_t _failsafe_priorities[] = {274Failsafe_Action_Terminate,275Failsafe_Action_Land,276Failsafe_Action_None,277-1 // the priority list must end with a sentinel of -1278};279280#define FAILSAFE_LAND_PRIORITY 1281static_assert(_failsafe_priorities[FAILSAFE_LAND_PRIORITY] == Failsafe_Action_Land,282"FAILSAFE_LAND_PRIORITY must match the entry in _failsafe_priorities");283static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,284"_failsafe_priorities is missing the sentinel");285286// AP_State.cpp287void set_auto_armed(bool b);288void set_failsafe_radio(bool b);289void set_failsafe_gcs(bool b);290291// Blimp.cpp292void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,293uint8_t &task_count,294uint32_t &log_bit) override;295void rc_loop();296void throttle_loop();297void update_batt_compass(void);298void full_rate_logging();299void ten_hz_logging_loop();300void twentyfive_hz_logging();301void three_hz_loop();302void one_hz_loop();303void read_AHRS(void);304void update_altitude();305void rotate_NE_to_BF(Vector2f &vec);306void rotate_BF_to_NE(Vector2f &vec);307308// commands.cpp309void update_home_from_EKF();310void set_home_to_current_location_inflight();311bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;312bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;313314// ekf_check.cpp315void ekf_check();316bool ekf_over_threshold();317void failsafe_ekf_event();318void failsafe_ekf_off_event(void);319void check_ekf_reset();320void check_vibration();321322// events.cpp323bool failsafe_option(FailsafeOption opt) const;324void failsafe_radio_on_event();325void failsafe_radio_off_event();326void handle_battery_failsafe(const char* type_str, const int8_t action);327void failsafe_gcs_check();328bool should_disarm_on_failsafe();329void do_failsafe_action(Failsafe_Action action, ModeReason reason);330void gpsglitch_check();331332// failsafe.cpp333void failsafe_enable();334void failsafe_disable();335336// fence.cpp337void fence_check();338339// inertia.cpp340void read_inertia();341342// landing_detector.cpp343void update_land_and_crash_detectors();344void update_land_detector();345346// landing_gear.cpp347void landinggear_update();348349#if HAL_LOGGING_ENABLED350// methods for AP_Vehicle:351const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }352const struct LogStructure *get_log_structures() const override {353return log_structure;354}355uint8_t get_num_log_structures() const override;356357// Log.cpp358void Log_Write_Attitude();359void Log_Write_PIDs();360void Log_Write_EKF_POS();361void Log_Write_Data(LogDataID id, int32_t value);362void Log_Write_Data(LogDataID id, uint32_t value);363void Log_Write_Data(LogDataID id, int16_t value);364void Log_Write_Data(LogDataID id, uint16_t value);365void Log_Write_Data(LogDataID id, float value);366void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max);367368369void Log_Write_Vehicle_Startup_Messages();370void Write_FINI(float right, float front, float down, float yaw);371void Write_FINO(float *amp, float *off);372#endif373374// mode.cpp375bool set_mode(Mode::Number mode, ModeReason reason);376bool set_mode(const uint8_t new_mode, const ModeReason reason) override;377uint8_t get_mode() const override378{379return (uint8_t)control_mode;380}381void update_flight_mode();382void notify_flight_mode();383384// mode_land.cpp385void set_mode_land_failsafe(ModeReason reason);386bool landing_with_GPS();387388// // motors.cpp389void arm_motors_check();390void motors_output();391392// Parameters.cpp393void load_parameters(void) override;394void convert_pid_parameters(void);395void convert_lgr_parameters(void);396void convert_fs_options_params(void);397398// radio.cpp399void default_dead_zones();400void init_rc_in();401void init_rc_out();402void enable_motor_output();403void read_radio();404void set_throttle_and_failsafe(uint16_t throttle_pwm);405void set_throttle_zero_flag(int16_t throttle_control);406407// sensors.cpp408void read_barometer(void);409void init_rangefinder(void);410void read_rangefinder(void);411bool rangefinder_alt_ok();412bool rangefinder_up_ok();413414// RC_Channel.cpp415void save_trim();416void auto_trim();417void auto_trim_cancel();418419// system.cpp420void init_ardupilot() override;421void startup_INS_ground();422bool position_ok() const;423bool ekf_has_absolute_position() const;424bool ekf_has_relative_position() const;425bool ekf_alt_ok() const;426void update_auto_armed();427bool should_log(uint32_t mask);428MAV_TYPE get_frame_mav_type();429const char* get_frame_string();430void allocate_motors(void);431432Mode *flightmode;433ModeManual mode_manual;434ModeLand mode_land;435ModeVelocity mode_velocity;436ModeLoiter mode_loiter;437ModeRTL mode_rtl;438439// mode.cpp440Mode *mode_from_mode_num(const Mode::Number mode);441void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);442443public:444void failsafe_check(); // failsafe.cpp445};446447extern Blimp blimp;448449using AP_HAL::millis;450using AP_HAL::micros;451452453