#pragma once
#include <AP_Common/AP_Common.h>
#include "RC_Channel_Rover.h"
#include <AC_Avoidance/AC_Avoid.h>
#include "AC_Sprayer/AC_Sprayer.h"
#include <AP_AIS/AP_AIS.h>
#include <AP_Beacon/AP_Beacon.h>
#include <AP_Follow/AP_Follow.h>
#include <AP_Proximity/AP_Proximity.h>
#include "AP_Rally.h"
#include <AP_SmartRTL/AP_SmartRTL.h>
#include <AP_Stats/AP_Stats.h>
#include "AP_Torqeedo/AP_Torqeedo.h"
#include <AP_WindVane/AP_WindVane.h>
#define AP_PARAM_VEHICLE_NAME rover
class Parameters {
public:
static const uint16_t k_format_version = 16;
enum {
k_param_format_version = 0,
k_param_software_type,
k_param_can_mgr,
k_param_log_bitmask_old = 10,
k_param_num_resets_old,
k_param_reset_switch_chan,
k_param_initial_mode,
k_param_scheduler,
k_param_relay,
k_param_BoardConfig,
k_param_pivot_turn_angle_old,
k_param_rc_13_old,
k_param_rc_14_old,
k_param_rssi_pin = 20,
k_param_battery_volt_pin,
k_param_battery_curr_pin,
k_param_precland = 24,
k_param_braking_percent_old = 30,
k_param_braking_speederr_old,
k_param_log_bitmask = 40,
k_param_gps,
k_param_serial0_baud,
k_param_serial1_baud,
k_param_serial2_baud,
k_param_rssi = 97,
k_param_rpm_sensor_old,
k_param_arming = 100,
k_param_gcs0_unused = 110,
k_param_gcs1_unused,
k_param_sysid_this_mav_old,
k_param_sysid_my_gcs_old,
k_param_serial0_baud_old,
k_param_serial1_baud_old,
k_param_telem_delay_old,
k_param_skip_gyro_cal,
k_param_gcs2_unused,
k_param_serial2_baud_old,
k_param_serial2_protocol,
k_param_serial_manager_old,
k_param_cli_enabled_old,
k_param_gcs3_unused,
k_param_gcs_pid_mask,
k_param_gcs4_unused,
k_param_gcs5_unused,
k_param_gcs6_unused,
k_param_compass_enabled_deprecated = 130,
k_param_steering_learn,
k_param_NavEKF,
k_param_mission,
k_param_NavEKF2_old,
k_param_NavEKF2,
k_param_g2,
k_param_NavEKF3,
k_param_battery_monitoring = 140,
k_param_volt_div_ratio,
k_param_curr_amp_per_volt,
k_param_input_voltage,
k_param_pack_capacity,
k_param_battery,
k_param_crosstrack_gain = 150,
k_param_crosstrack_entry_angle,
k_param_speed_cruise,
k_param_speed_turn_gain,
k_param_speed_turn_dist,
k_param_ch7_option,
k_param_auto_trigger_pin,
k_param_auto_kickstart,
k_param_turn_circle,
k_param_turn_max_g_old,
k_param_rc_1_old = 160,
k_param_rc_2_old,
k_param_rc_3_old,
k_param_rc_4_old,
k_param_rc_5_old,
k_param_rc_6_old,
k_param_rc_7_old,
k_param_rc_8_old,
k_param_throttle_min_old = 170,
k_param_throttle_max_old,
k_param_throttle_cruise,
k_param_throttle_slewrate_old,
k_param_throttle_reduction,
k_param_pilot_steer_type,
k_param_skid_steer_out_old,
k_param_fs_action = 180,
k_param_fs_timeout,
k_param_fs_throttle_enabled,
k_param_fs_throttle_value,
k_param_fs_gcs_enabled,
k_param_fs_crash_check,
k_param_fs_ekf_action,
k_param_fs_ekf_thresh,
k_param_sonar_enabled = 190,
k_param_sonar_old,
k_param_rangefinder_trigger_cm,
k_param_rangefinder_turn_angle,
k_param_rangefinder_turn_time,
k_param_sonar2_old,
k_param_rangefinder_debounce,
k_param_rangefinder,
k_param_mode_channel = 210,
k_param_mode1,
k_param_mode2,
k_param_mode3,
k_param_mode4,
k_param_mode5,
k_param_mode6,
k_param_aux_channel_old,
k_param_command_total = 220,
k_param_command_index,
k_param_waypoint_radius_old,
k_param_waypoint_overshoot_old,
k_param_camera,
k_param_camera_mount,
k_param_camera_mount2,
k_param_pidNavSteer = 230,
k_param_pidServoSteer,
k_param_pidSpeedThrottle_old,
k_param_rc_9_old = 235,
k_param_rc_10_old,
k_param_rc_11_old,
k_param_rc_12_old,
k_param_sitl = 240,
k_param_ahrs,
k_param_ins,
k_param_compass,
k_param_rcmap,
k_param_L1_controller,
k_param_steerController_old,
k_param_barometer,
k_param_notify,
k_param_button,
k_param_osd,
k_param_optflow,
k_param_logger = 253,
k_param_vehicle = 257,
k_param__gcs = 258,
};
AP_Int16 format_version;
AP_Int32 log_bitmask;
AP_Int8 reset_switch_chan;
AP_Int8 initial_mode;
AP_Float speed_cruise;
AP_Int8 ch7_option;
AP_Int8 auto_trigger_pin;
AP_Float auto_kickstart;
AP_Int16 gcs_pid_mask;
AP_Int8 throttle_cruise;
AP_Enum<PilotSteerType> pilot_steer_type;
AP_Int8 fs_action;
AP_Float fs_timeout;
AP_Int8 fs_throttle_enabled;
AP_Int16 fs_throttle_value;
AP_Int8 fs_gcs_enabled;
AP_Int8 fs_crash_check;
AP_Int8 fs_ekf_action;
AP_Float fs_ekf_thresh;
AP_Int8 mode_channel;
AP_Int8 mode1;
AP_Int8 mode2;
AP_Int8 mode3;
AP_Int8 mode4;
AP_Int8 mode5;
AP_Int8 mode6;
Parameters() {}
};
class ParametersG2 {
public:
ParametersG2(void);
static const struct AP_Param::GroupInfo var_info[];
RC_Channels_Rover rc_channels;
SRV_Channels servo_channels;
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
AP_AdvancedFailsafe_Rover afs;
#endif
#if AP_BEACON_ENABLED
AP_Beacon beacon;
#endif
AP_WheelEncoder wheel_encoder;
AP_WheelRateControl wheel_rate_control;
AP_MotorsUGV motors;
AR_AttitudeControl attitude_control;
AP_Float turn_radius;
AP_Float acro_turn_rate;
AP_SmartRTL smart_rtl;
AP_Float rtl_speed;
AP_Int8 frame_class;
#if HAL_PROXIMITY_ENABLED
AP_Proximity proximity;
#endif
#if MODE_DOCK_ENABLED
class ModeDock *mode_dock_ptr;
#endif
#if AP_AVOIDANCE_ENABLED
AC_Avoid avoid;
#endif
AP_Float bal_pitch_max;
AP_Int8 crash_angle;
#if AP_FOLLOW_ENABLED
AP_Follow follow;
#endif
AP_Int8 frame_type;
AP_Int8 loit_type;
AP_Float loit_radius;
#if HAL_SPRAYER_ENABLED
AC_Sprayer sprayer;
#endif
#if HAL_RALLY_ENABLED
AP_Rally_Rover rally;
#endif
AP_Int8 simple_type;
AP_WindVane windvane;
#if AP_MISSION_ENABLED
AP_Enum<ModeAuto::DoneBehaviour> mis_done_behave;
#endif
AP_Float bal_pitch_trim;
AP_Int8 stick_mixing;
AR_WPNav_OA wp_nav;
Sailboat sailboat;
#if AP_OAPATHPLANNER_ENABLED
AP_OAPathPlanner oa;
#endif
AP_Float speed_max;
AP_Float loiter_speed_gain;
AP_Int32 fs_options;
#if HAL_TORQEEDO_ENABLED
AP_Torqeedo torqeedo;
#endif
AR_PosControl pos_control;
AP_Int32 guided_options;
AP_Int32 manual_options;
AP_Float manual_steering_expo;
AP_Float fs_gcs_timeout;
class ModeCircle mode_circle;
};
extern const AP_Param::Info var_info[];