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/Parameters.h
Views: 1798
#pragma once12#define AP_PARAM_VEHICLE_NAME blimp34#include <AP_Common/AP_Common.h>5#include "RC_Channel_Blimp.h"6#include <SRV_Channel/SRV_Channel.h>78// Global parameter class.9//10class Parameters11{12public:13// The version of the layout as described by the parameter enum.14//15// When changing the parameter enum in an incompatible fashion, this16// value should be incremented by one.17//18// The increment will prevent old parameters from being used incorrectly19// by newer code.20//21static const uint16_t k_format_version = 1;2223// Parameter identities.24//25// The enumeration defined here is used to ensure that every parameter26// or parameter group has a unique ID number. This number is used by27// AP_Param to store and locate parameters in EEPROM.28//29// Note that entries without a number are assigned the next number after30// the entry preceding them. When adding new entries, ensure that they31// don't overlap.32//33// Try to group related variables together, and assign them a set34// range in the enumeration. Place these groups in numerical order35// at the end of the enumeration.36//37// WARNING: Care should be taken when editing this enumeration as the38// AP_Param load/save code depends on the values here to identify39// variables saved in EEPROM.40//41//42enum {43// Layout version number, always key zero.44//45k_param_format_version = 0,46k_param_ins, // libraries/AP_InertialSensor variables47k_param_NavEKF2,48k_param_g2, // 2nd block of parameters49k_param_NavEKF3,50k_param_can_mgr,51k_param_osd,5253// simulation54k_param_sitl = 10,5556// barometer object (needed for SITL)57k_param_barometer,5859// scheduler object (for debugging)60k_param_scheduler,6162// BoardConfig object63k_param_BoardConfig,6465// GPS object66k_param_gps,6768// Parachute object69k_param_parachute,7071// Landing gear object72k_param_landinggear,7374// Input Management object75k_param_input_manager,7677// Misc78k_param_gps_hdop_good,79k_param_battery,80k_param_poshold_brake_rate,81k_param_poshold_brake_angle_max,82k_param_pilot_accel_z,83k_param_fs_ekf_thresh,84k_param_terrain,85k_param_throttle_deadzone,86k_param_log_bitmask,87k_param_throttle_filt,88k_param_throttle_behavior,89k_param_pilot_takeoff_alt, //unused9091// AP_ADSB Library92k_param_adsb,93k_param_notify,9495//PID Controllers96k_param_pid_vel_xy = 32,97k_param_pid_vel_z,98k_param_pid_vel_yaw,99k_param_pid_pos_xy,100k_param_pid_pos_z,101k_param_pid_pos_yaw,102103//Position & Velocity controller params104k_param_max_vel_xy = 50,105k_param_max_vel_z,106k_param_max_vel_yaw,107k_param_max_pos_xy,108k_param_max_pos_z,109k_param_max_pos_yaw,110k_param_simple_mode,111k_param_dis_mask,112k_param_pid_dz,113114//115// 90: misc2116//117k_param_motors = 90,118k_param_disarm_delay,119k_param_fs_crash_check,120k_param_throw_motor_start,121k_param_rtl_alt_type,122k_param_avoid,123k_param_avoidance_adsb,124125// 97: RSSI126k_param_rssi = 97,127128// 110: Telemetry control129//130k_param_gcs0 = 110,131k_param_gcs1,132k_param_sysid_this_mav,133k_param_sysid_my_gcs,134k_param_telem_delay,135k_param_gcs2,136k_param_serial_manager_old,137k_param_gcs3,138k_param_gcs_pid_mask,139k_param_gcs4,140k_param_gcs5,141k_param_gcs6,142143//144// 135 : reserved for Solo until features merged with master145//146k_param_rtl_speed_cms = 135,147k_param_fs_batt_curr_rtl,148k_param_rtl_cone_slope, // 137149150//151// 140: Sensor parameters152//153k_param_compass,154k_param_frame_type, //unused155k_param_ahrs, // AHRS group // 159156157//158// 160: Navigation parameters159//160k_param_rtl_altitude = 160,161k_param_rtl_loiter_time,162k_param_rtl_alt_final,163164165//166// Camera and mount parameters167//168k_param_camera = 165,169k_param_camera_mount,170171//172// 170: Radio settings173//174k_param_failsafe_throttle = 170,175k_param_failsafe_throttle_value,176k_param_radio_tuning, // unused177k_param_rc_speed = 192,178k_param_failsafe_gcs,179k_param_rcmap, // 199180181//182// 200: flight modes183//184k_param_flight_mode1 = 200,185k_param_flight_mode2,186k_param_flight_mode3,187k_param_flight_mode4,188k_param_flight_mode5,189k_param_flight_mode6,190k_param_flight_mode_chan,191k_param_initial_mode,192193//194// 220: Misc195//196k_param_fs_ekf_action = 220,197k_param_arming,198199k_param_logger = 253, // 253 - Logging Group200201k_param_vehicle = 257, // vehicle common block of parameters202203// the k_param_* space is 9-bits in size204};205206AP_Int16 format_version;207208// Telemetry control209//210AP_Int16 sysid_this_mav;211AP_Int16 sysid_my_gcs;212AP_Int8 telem_delay;213214AP_Float throttle_filt;215AP_Int16 throttle_behavior;216217AP_Int8 failsafe_gcs; // ground station failsafe behavior218AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position219220// Throttle221//222AP_Int8 failsafe_throttle;223AP_Int16 failsafe_throttle_value;224AP_Int16 throttle_deadzone;225226// Flight modes227//228AP_Int8 flight_mode1;229AP_Int8 flight_mode2;230AP_Int8 flight_mode3;231AP_Int8 flight_mode4;232AP_Int8 flight_mode5;233AP_Int8 flight_mode6;234AP_Int8 flight_mode_chan;235AP_Int8 initial_mode;236237// Misc238//239AP_Int32 log_bitmask;240AP_Int8 disarm_delay;241242AP_Int8 fs_ekf_action;243AP_Int8 fs_crash_check;244AP_Float fs_ekf_thresh;245AP_Int16 gcs_pid_mask;246247AP_Float max_vel_xy;248AP_Float max_vel_z;249AP_Float max_vel_yaw;250AP_Float max_pos_xy;251AP_Float max_pos_z;252AP_Float max_pos_yaw;253254AP_Int8 simple_mode;255AP_Int16 dis_mask;256AP_Float pid_dz;257258AP_Int8 rtl_alt_type;259260AP_Int16 rc_speed; // speed of fast RC Channels in Hz261262// Note: keep initializers here in the same order as they are declared263// above.264Parameters()265{266}267};268269/*2702nd block of parameters, to avoid going past 256 top level keys271*/272class ParametersG2273{274public:275ParametersG2(void);276277// var_info for holding Parameter information278static const struct AP_Param::GroupInfo var_info[];279280// altitude at which nav control can start in takeoff281AP_Float wp_navalt_min;282283// whether to enforce acceptance of packets only from sysid_my_gcs284AP_Int8 sysid_enforce;285286// developer options287AP_Int32 dev_options;288289// acro exponent parameters290AP_Float acro_y_expo;291292// frame class293AP_Int8 frame_class;294295// RC input channels296RC_Channels_Blimp rc_channels;297298// control over servo output ranges299SRV_Channels servo_channels;300301// Additional pilot velocity items302AP_Int16 pilot_speed_dn;303304// Land alt final stage305AP_Int16 land_alt_low;306307// vibration failsafe enable/disable308AP_Int8 fs_vibe_enabled;309310// Failsafe options bitmask #36311AP_Int32 fs_options;312313AP_Float fs_gcs_timeout;314};315316extern const AP_Param::Info var_info[];317318319