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/Parameters.h
Views: 1798
#pragma once12#include <AP_Common/AP_Common.h>34#include "RC_Channel_Rover.h"5#include <AC_Avoidance/AC_Avoid.h>6#include "AC_Sprayer/AC_Sprayer.h"7#include <AP_AIS/AP_AIS.h>8#include <AP_Beacon/AP_Beacon.h>9#include <AP_Follow/AP_Follow.h>10#include <AP_Proximity/AP_Proximity.h>11#include "AP_Rally.h"12#include <AP_SmartRTL/AP_SmartRTL.h>13#include <AP_Stats/AP_Stats.h>14#include "AP_Torqeedo/AP_Torqeedo.h"15#include <AP_WindVane/AP_WindVane.h>1617#define AP_PARAM_VEHICLE_NAME rover1819// Global parameter class.20//21class Parameters {22public:23// The version of the layout as described by the parameter enum.24//25// When changing the parameter enum in an incompatible fashion, this26// value should be incremented by one.27//28// The increment will prevent old parameters from being used incorrectly29// by newer code.30//31static const uint16_t k_format_version = 16;3233enum {34// Layout version number, always key zero.35//36k_param_format_version = 0,37k_param_software_type, // unused38k_param_can_mgr,3940// Misc41//42k_param_log_bitmask_old = 10, // unused43k_param_num_resets_old, // unused44k_param_reset_switch_chan,45k_param_initial_mode,46k_param_scheduler,47k_param_relay,48k_param_BoardConfig,49k_param_pivot_turn_angle_old, // unused50k_param_rc_13_old, // unused51k_param_rc_14_old, // unused5253// IO pins54k_param_rssi_pin = 20, // unused, replaced by rssi_ library parameters55k_param_battery_volt_pin,56k_param_battery_curr_pin,5758k_param_precland = 24,5960// braking61k_param_braking_percent_old = 30, // unused62k_param_braking_speederr_old, // unused6364// misc265k_param_log_bitmask = 40,66k_param_gps,67k_param_serial0_baud, // deprecated, can be deleted68k_param_serial1_baud, // deprecated, can be deleted69k_param_serial2_baud, // deprecated, can be deleted7071// 97: RSSI72k_param_rssi = 97,73k_param_rpm_sensor, // rpm sensor 987475// 100: Arming parameters76k_param_arming = 100,7778// 110: Telemetry control79//80k_param_gcs0 = 110, // stream rates for SERIAL081k_param_gcs1, // stream rates for SERIAL182k_param_sysid_this_mav,83k_param_sysid_my_gcs,84k_param_serial0_baud_old, // unused85k_param_serial1_baud_old, // unused86k_param_telem_delay,87k_param_skip_gyro_cal, // unused88k_param_gcs2, // stream rates for SERIAL289k_param_serial2_baud_old, // unused90k_param_serial2_protocol, // deprecated, can be deleted91k_param_serial_manager_old, // serial manager library92k_param_cli_enabled_old, // unused93k_param_gcs3,94k_param_gcs_pid_mask,95k_param_gcs4,96k_param_gcs5,97k_param_gcs6,9899//100// 130: Sensor parameters101//102k_param_compass_enabled_deprecated = 130,103k_param_steering_learn, // unused104k_param_NavEKF, // deprecated - remove105k_param_mission, // mission library106k_param_NavEKF2_old, // deprecated - remove107k_param_NavEKF2,108k_param_g2, // 2nd block of parameters109k_param_NavEKF3,110111// 140: battery controls112k_param_battery_monitoring = 140, // deprecated, can be deleted113k_param_volt_div_ratio, // deprecated, can be deleted114k_param_curr_amp_per_volt, // deprecated, can be deleted115k_param_input_voltage, // deprecated, can be deleted116k_param_pack_capacity, // deprecated, can be deleted117k_param_battery,118119//120// 150: Navigation parameters121//122k_param_crosstrack_gain = 150, // unused123k_param_crosstrack_entry_angle, // unused124k_param_speed_cruise,125k_param_speed_turn_gain, // unused126k_param_speed_turn_dist, // unused127k_param_ch7_option, // unused128k_param_auto_trigger_pin,129k_param_auto_kickstart,130k_param_turn_circle, // unused131k_param_turn_max_g_old, // unused132133//134// 160: Radio settings135//136k_param_rc_1_old = 160, // unused137k_param_rc_2_old, // unused138k_param_rc_3_old, // unused139k_param_rc_4_old, // unused140k_param_rc_5_old, // unused141k_param_rc_6_old, // unused142k_param_rc_7_old, // unused143k_param_rc_8_old, // unused144145// throttle control146k_param_throttle_min_old = 170, // unused147k_param_throttle_max_old, // unused148k_param_throttle_cruise,149k_param_throttle_slewrate_old, // unused150k_param_throttle_reduction, // unused151k_param_pilot_steer_type,152k_param_skid_steer_out_old, // unused153154// failsafe control155k_param_fs_action = 180,156k_param_fs_timeout,157k_param_fs_throttle_enabled,158k_param_fs_throttle_value,159k_param_fs_gcs_enabled,160k_param_fs_crash_check,161k_param_fs_ekf_action,162k_param_fs_ekf_thresh, // 187163164// obstacle control165k_param_sonar_enabled = 190, // deprecated, can be removed166k_param_sonar_old, // unused167k_param_rangefinder_trigger_cm, // unused168k_param_rangefinder_turn_angle, // unused169k_param_rangefinder_turn_time, // unused170k_param_sonar2_old, // unused171k_param_rangefinder_debounce, // unused172k_param_rangefinder, // rangefinder object173174//175// 210: driving modes176//177k_param_mode_channel = 210,178k_param_mode1,179k_param_mode2,180k_param_mode3,181k_param_mode4,182k_param_mode5,183k_param_mode6,184k_param_aux_channel_old,185186//187// 220: Waypoint data188//189k_param_command_total = 220, // unused190k_param_command_index, // unused191k_param_waypoint_radius_old, // unused192k_param_waypoint_overshoot_old, // unused193194//195// camera control196//197k_param_camera,198k_param_camera_mount,199k_param_camera_mount2, // unused200201//202// 230: PID Controllers203k_param_pidNavSteer = 230,204k_param_pidServoSteer, // unused205k_param_pidSpeedThrottle_old, // unused206207// high RC channels208k_param_rc_9_old = 235, // unused209k_param_rc_10_old, // unused210k_param_rc_11_old, // unused211k_param_rc_12_old, // unusedS212213// other objects214k_param_sitl = 240,215k_param_ahrs,216k_param_ins,217k_param_compass,218k_param_rcmap,219k_param_L1_controller, // unused220k_param_steerController_old, // unused221k_param_barometer,222k_param_notify,223k_param_button,224k_param_osd,225k_param_optflow,226227k_param_logger = 253, // Logging Group228229// 254,255: reserved230231k_param_vehicle = 257, // vehicle common block of parameters232};233234AP_Int16 format_version;235236// Misc237//238AP_Int32 log_bitmask;239AP_Int8 reset_switch_chan;240AP_Int8 initial_mode;241242// Telemetry control243//244AP_Int16 sysid_this_mav;245AP_Int16 sysid_my_gcs;246AP_Int8 telem_delay;247248// navigation parameters249//250AP_Float speed_cruise;251AP_Int8 ch7_option;252AP_Int8 auto_trigger_pin;253AP_Float auto_kickstart;254AP_Int16 gcs_pid_mask;255256// Throttle257//258AP_Int8 throttle_cruise;259AP_Enum<PilotSteerType> pilot_steer_type;260261// failsafe control262AP_Int8 fs_action;263AP_Float fs_timeout;264AP_Int8 fs_throttle_enabled;265AP_Int16 fs_throttle_value;266AP_Int8 fs_gcs_enabled;267AP_Int8 fs_crash_check;268AP_Int8 fs_ekf_action;269AP_Float fs_ekf_thresh;270271// driving modes272//273AP_Int8 mode_channel;274AP_Int8 mode1;275AP_Int8 mode2;276AP_Int8 mode3;277AP_Int8 mode4;278AP_Int8 mode5;279AP_Int8 mode6;280281Parameters() {}282};283284/*2852nd block of parameters, to avoid going past 256 top level keys286*/287class ParametersG2 {288public:289ParametersG2(void);290291// var_info for holding Parameter information292static const struct AP_Param::GroupInfo var_info[];293294// whether to enforce acceptance of packets only from sysid_my_gcs295AP_Int8 sysid_enforce;296297// RC input channels298RC_Channels_Rover rc_channels;299300// control over servo output ranges301SRV_Channels servo_channels;302303#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED304// advanced failsafe library305AP_AdvancedFailsafe_Rover afs;306#endif307308#if AP_BEACON_ENABLED309AP_Beacon beacon;310#endif311312// wheel encoders313AP_WheelEncoder wheel_encoder;314AP_WheelRateControl wheel_rate_control;315316// Motor library317AP_MotorsUGV motors;318319// steering and throttle controller320AR_AttitudeControl attitude_control;321322// turn radius of vehicle (only used in steering mode)323AP_Float turn_radius;324325// acro mode turn rate maximum326AP_Float acro_turn_rate;327328// Safe RTL library329AP_SmartRTL smart_rtl;330331// default speed for rtl332AP_Float rtl_speed;333334// frame class for vehicle335AP_Int8 frame_class;336337#if HAL_PROXIMITY_ENABLED338// proximity library339AP_Proximity proximity;340#endif341342#if MODE_DOCK_ENABLED343// we need a pointer to the mode for the G2 table344class ModeDock *mode_dock_ptr;345#endif346347#if AP_AVOIDANCE_ENABLED348// avoidance library349AC_Avoid avoid;350#endif351352// pitch angle at 100% throttle353AP_Float bal_pitch_max;354355// pitch/roll angle for crash check356AP_Int8 crash_angle;357358#if AP_FOLLOW_ENABLED359// follow mode library360AP_Follow follow;361#endif362363// frame type for vehicle (used for vectored motor vehicles and custom motor configs)364AP_Int8 frame_type;365366// loiter type367AP_Int8 loit_type;368AP_Float loit_radius;369370#if HAL_SPRAYER_ENABLED371// Sprayer372AC_Sprayer sprayer;373#endif374375#if HAL_RALLY_ENABLED376// Rally point library377AP_Rally_Rover rally;378#endif379380// Simple mode types381AP_Int8 simple_type;382383// windvane384AP_WindVane windvane;385386#if AP_MISSION_ENABLED387// mission behave388AP_Enum<ModeAuto::DoneBehaviour> mis_done_behave;389#endif390391// balance both pitch trim392AP_Float bal_pitch_trim;393394// stick mixing for auto modes395AP_Int8 stick_mixing;396397// waypoint navigation398AR_WPNav_OA wp_nav;399400// Sailboat functions401Sailboat sailboat;402403#if AP_OAPATHPLANNER_ENABLED404// object avoidance path planning405AP_OAPathPlanner oa;406#endif407408// maximum speed for vehicle409AP_Float speed_max;410411// gain for speed of correction in loiter412AP_Float loiter_speed_gain;413414// FS options415AP_Int32 fs_options;416417#if HAL_TORQEEDO_ENABLED418// torqeedo motor driver419AP_Torqeedo torqeedo;420#endif421422// position controller423AR_PosControl pos_control;424425// guided options bitmask426AP_Int32 guided_options;427428// manual mode options429AP_Int32 manual_options;430431// manual mode steering expo432AP_Float manual_steering_expo;433434// FS GCS timeout trigger time435AP_Float fs_gcs_timeout;436437class ModeCircle mode_circle;438};439440extern const AP_Param::Info var_info[];441442443