mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Param: updated APMrover2 code for new AP_Param syntax
This commit is contained in:
parent
c2a4d59132
commit
dfac01e6f1
@ -385,7 +385,6 @@ This feature works only if the ROV_AWPR_NAV is set to 0
|
||||
#define THROTTLE_TE_I 0.0
|
||||
#define THROTTLE_TE_D 0.0
|
||||
#define THROTTLE_TE_INT_MAX 20
|
||||
#define THROTTLE_SLEW_LIMIT 0
|
||||
#define P_TO_T 0.0
|
||||
#define T_TO_P 0
|
||||
|
||||
|
@ -131,6 +131,12 @@ FastSerialPort1(Serial1); // GPS port
|
||||
FastSerialPort3(Serial3); // Telemetry port for APM1
|
||||
#endif
|
||||
|
||||
// this sets up the parameter table, and sets the default values. This
|
||||
// must be the first AP_Param variable declared to ensure its
|
||||
// constructor runs before the constructors of the other AP_Param
|
||||
// variables
|
||||
AP_Param param_loader(var_info, WP_START_BYTE);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// ISR Registry
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -723,15 +723,15 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char
|
||||
}
|
||||
|
||||
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRateRawSensors),
|
||||
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRateExtendedStatus),
|
||||
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRateRCChannels),
|
||||
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRateRawController),
|
||||
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRatePosition),
|
||||
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRateExtra1),
|
||||
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRateExtra2),
|
||||
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRateExtra3),
|
||||
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRateParams),
|
||||
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRateRawSensors, 0),
|
||||
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRateExtendedStatus, 0),
|
||||
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRateRCChannels, 0),
|
||||
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRateRawController, 0),
|
||||
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRatePosition, 0),
|
||||
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRateExtra1, 0),
|
||||
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRateExtra2, 0),
|
||||
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRateExtra3, 0),
|
||||
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRateParams, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -379,127 +379,15 @@ public:
|
||||
PID pidNavPitchAltitude;
|
||||
|
||||
Parameters() :
|
||||
format_version (k_format_version),
|
||||
software_type (k_software_type),
|
||||
|
||||
sysid_this_mav (MAV_SYSTEM_ID),
|
||||
sysid_my_gcs (255),
|
||||
serial3_baud (SERIAL3_BAUD/1000),
|
||||
|
||||
kff_pitch_compensation (PITCH_COMP),
|
||||
kff_rudder_mix (RUDDER_MIX),
|
||||
kff_pitch_to_throttle (P_TO_T),
|
||||
kff_throttle_to_pitch (T_TO_P),
|
||||
|
||||
crosstrack_gain (XTRACK_GAIN_SCALED),
|
||||
crosstrack_entry_angle (XTRACK_ENTRY_ANGLE_CENTIDEGREE),
|
||||
|
||||
altitude_mix (ALTITUDE_MIX),
|
||||
airspeed_ratio (AIRSPEED_RATIO),
|
||||
airspeed_offset (0),
|
||||
|
||||
/* XXX waypoint_mode missing here */
|
||||
command_total (0),
|
||||
command_index (0),
|
||||
waypoint_radius (WP_RADIUS_DEFAULT),
|
||||
loiter_radius (LOITER_RADIUS_DEFAULT),
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
fence_action (0),
|
||||
fence_total (0),
|
||||
fence_channel (0),
|
||||
fence_minalt (0),
|
||||
fence_maxalt (0),
|
||||
#endif
|
||||
|
||||
flybywire_airspeed_min (AIRSPEED_FBW_MIN),
|
||||
flybywire_airspeed_max (AIRSPEED_FBW_MAX),
|
||||
|
||||
throttle_min (THROTTLE_MIN),
|
||||
throttle_max (THROTTLE_MAX),
|
||||
throttle_slewrate (THROTTLE_SLEW_LIMIT),
|
||||
throttle_fs_enabled (THROTTLE_FAILSAFE),
|
||||
throttle_fs_value (THROTTLE_FS_VALUE),
|
||||
throttle_cruise (THROTTLE_CRUISE),
|
||||
|
||||
short_fs_action (SHORT_FAILSAFE_ACTION),
|
||||
long_fs_action (LONG_FAILSAFE_ACTION),
|
||||
gcs_heartbeat_fs_enabled(GCS_HEARTBEAT_FAILSAFE),
|
||||
|
||||
flight_mode_channel (FLIGHT_MODE_CHANNEL),
|
||||
flight_mode1 (FLIGHT_MODE_1),
|
||||
flight_mode2 (FLIGHT_MODE_2),
|
||||
flight_mode3 (FLIGHT_MODE_3),
|
||||
flight_mode4 (FLIGHT_MODE_4),
|
||||
flight_mode5 (FLIGHT_MODE_5),
|
||||
flight_mode6 (FLIGHT_MODE_6),
|
||||
|
||||
roll_limit (HEAD_MAX_CENTIDEGREE),
|
||||
pitch_limit_max (PITCH_MAX_CENTIDEGREE),
|
||||
pitch_limit_min (PITCH_MIN_CENTIDEGREE),
|
||||
|
||||
auto_trim (AUTO_TRIM),
|
||||
manual_level (MANUAL_LEVEL),
|
||||
|
||||
switch_enable (REVERSE_SWITCH),
|
||||
mix_mode (ELEVON_MIXING),
|
||||
reverse_elevons (ELEVON_REVERSE),
|
||||
reverse_ch1_elevon (ELEVON_CH1_REVERSE),
|
||||
reverse_ch2_elevon (ELEVON_CH2_REVERSE),
|
||||
num_resets (0),
|
||||
log_bitmask (DEFAULT_LOG_BITMASK),
|
||||
log_last_filenumber (0),
|
||||
reset_switch_chan (0),
|
||||
airspeed_cruise (AIRSPEED_CRUISE_CM),
|
||||
min_gndspeed (MIN_GNDSPEED_CM),
|
||||
ch7_option (CH7_OPTION),
|
||||
pitch_trim (0),
|
||||
RTL_altitude (ALT_HOLD_HOME_CM),
|
||||
FBWB_min_altitude (ALT_HOLD_FBW_CM),
|
||||
|
||||
ground_temperature (0),
|
||||
ground_pressure (0),
|
||||
compass_enabled (MAGNETOMETER),
|
||||
flap_1_percent (FLAP_1_PERCENT),
|
||||
flap_1_speed (FLAP_1_SPEED),
|
||||
flap_2_percent (FLAP_2_PERCENT),
|
||||
flap_2_speed (FLAP_2_SPEED),
|
||||
|
||||
|
||||
battery_monitoring (DISABLED),
|
||||
volt_div_ratio (VOLT_DIV_RATIO),
|
||||
curr_amp_per_volt (CURR_AMP_PER_VOLT),
|
||||
input_voltage (INPUT_VOLTAGE),
|
||||
pack_capacity (HIGH_DISCHARGE),
|
||||
inverted_flight_ch (0),
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
sonar_enabled (SONAR_ENABLED),
|
||||
sonar_type (AP_RANGEFINDER_MAXSONARXL),
|
||||
#endif
|
||||
#endif
|
||||
airspeed_enabled (AIRSPEED_SENSOR),
|
||||
|
||||
// ************ APMrover parameters ************************
|
||||
// - JLN update
|
||||
|
||||
closed_loop_nav (CLOSED_LOOP_NAV),
|
||||
auto_wp_radius (AUTO_WP_RADIUS),
|
||||
sonar_trigger (SONAR_TRIGGER),
|
||||
turn_gain (TURN_GAIN),
|
||||
booster (BOOSTER),
|
||||
|
||||
// ************************************************************
|
||||
|
||||
channel_roll (CH_1),
|
||||
channel_pitch (CH_2),
|
||||
channel_throttle (CH_3),
|
||||
channel_rudder (CH_4),
|
||||
rc_5 (CH_5),
|
||||
rc_6 (CH_6),
|
||||
rc_7 (CH_7),
|
||||
rc_8 (CH_8),
|
||||
|
||||
// RC channels
|
||||
channel_roll(CH_1),
|
||||
channel_pitch(CH_2),
|
||||
channel_throttle(CH_3),
|
||||
channel_rudder(CH_4),
|
||||
rc_5(CH_5),
|
||||
rc_6(CH_6),
|
||||
rc_7(CH_7),
|
||||
rc_8(CH_8),
|
||||
|
||||
// PID controller initial P initial I initial D initial imax
|
||||
//-----------------------------------------------------------------------------------
|
||||
@ -513,6 +401,8 @@ public:
|
||||
{}
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
||||
#endif // PARAMETERS_H
|
||||
|
||||
/* ************ ThermoPilot parameters (old parameters setup ) ************************
|
||||
|
@ -9,101 +9,101 @@
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
*/
|
||||
|
||||
#define GSCALAR(v, name) { g.v.vtype, name, Parameters::k_param_ ## v, &g.v }
|
||||
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &g.v, class::var_info }
|
||||
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &v, class::var_info }
|
||||
#define GSCALAR(v, name, def) { g.v.vtype, name, Parameters::k_param_ ## v, &g.v, {def_value:def} }
|
||||
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &g.v, {group_info:class::var_info} }
|
||||
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &v, {group_info:class::var_info} }
|
||||
|
||||
static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(format_version, "FORMAT_VERSION"),
|
||||
GSCALAR(software_type, "SYSID_SW_TYPE"),
|
||||
GSCALAR(sysid_this_mav, "SYSID_THISMAV"),
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS"),
|
||||
GSCALAR(serial3_baud, "SERIAL3_BAUD"),
|
||||
GSCALAR(kff_pitch_compensation, "KFF_PTCHCOMP"),
|
||||
GSCALAR(kff_rudder_mix, "KFF_RDDRMIX"),
|
||||
GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR"),
|
||||
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH"),
|
||||
GSCALAR(manual_level, "MANUAL_LEVEL"),
|
||||
const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(format_version, "FORMAT_VERSION", 0),
|
||||
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
|
||||
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
|
||||
GSCALAR(kff_pitch_compensation, "KFF_PTCHCOMP", PITCH_COMP),
|
||||
GSCALAR(kff_rudder_mix, "KFF_RDDRMIX", RUDDER_MIX),
|
||||
GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR", P_TO_T),
|
||||
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", T_TO_P),
|
||||
GSCALAR(manual_level, "MANUAL_LEVEL", 0),
|
||||
|
||||
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC"),
|
||||
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD"),
|
||||
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", XTRACK_GAIN_SCALED),
|
||||
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD", XTRACK_ENTRY_ANGLE_CENTIDEGREE),
|
||||
|
||||
GSCALAR(altitude_mix, "ALT_MIX"),
|
||||
GSCALAR(airspeed_ratio, "ARSPD_RATIO"),
|
||||
GSCALAR(airspeed_offset, "ARSPD_OFFSET"),
|
||||
GSCALAR(altitude_mix, "ALT_MIX", ALTITUDE_MIX),
|
||||
GSCALAR(airspeed_ratio, "ARSPD_RATIO", AIRSPEED_RATIO),
|
||||
GSCALAR(airspeed_offset, "ARSPD_OFFSET", 0),
|
||||
|
||||
GSCALAR(command_total, "CMD_TOTAL"),
|
||||
GSCALAR(command_index, "CMD_INDEX"),
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS"),
|
||||
GSCALAR(loiter_radius, "WP_LOITER_RAD"),
|
||||
GSCALAR(command_total, "CMD_TOTAL", 0),
|
||||
GSCALAR(command_index, "CMD_INDEX", 0),
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),
|
||||
GSCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
GSCALAR(fence_action, "FENCE_ACTION"),
|
||||
GSCALAR(fence_total, "FENCE_TOTAL"),
|
||||
GSCALAR(fence_channel, "FENCE_CHANNEL"),
|
||||
GSCALAR(fence_minalt, "FENCE_MINALT"),
|
||||
GSCALAR(fence_maxalt, "FENCE_MAXALT"),
|
||||
GSCALAR(fence_action, "FENCE_ACTION", 0),
|
||||
GSCALAR(fence_total, "FENCE_TOTAL", 0),
|
||||
GSCALAR(fence_channel, "FENCE_CHANNEL", 0),
|
||||
GSCALAR(fence_minalt, "FENCE_MINALT", 0),
|
||||
GSCALAR(fence_maxalt, "FENCE_MAXALT", 0),
|
||||
#endif
|
||||
|
||||
GSCALAR(flybywire_airspeed_min, "ARSPD_FBW_MIN"),
|
||||
GSCALAR(flybywire_airspeed_max, "ARSPD_FBW_MAX"),
|
||||
GSCALAR(flybywire_airspeed_min, "ARSPD_FBW_MIN", AIRSPEED_FBW_MIN),
|
||||
GSCALAR(flybywire_airspeed_max, "ARSPD_FBW_MAX", AIRSPEED_FBW_MAX),
|
||||
|
||||
GSCALAR(throttle_min, "THR_MIN"),
|
||||
GSCALAR(throttle_max, "THR_MAX"),
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE"),
|
||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE"),
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE"),
|
||||
GSCALAR(throttle_cruise, "TRIM_THROTTLE"),
|
||||
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
|
||||
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE", THROTTLE_SLEW_LIMIT),
|
||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", THROTTLE_FAILSAFE),
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE", THROTTLE_FS_VALUE),
|
||||
GSCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
|
||||
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN"),
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN"),
|
||||
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL"),
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN", SHORT_FAILSAFE_ACTION),
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN", LONG_FAILSAFE_ACTION),
|
||||
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_HEARTBEAT_FAILSAFE),
|
||||
|
||||
GSCALAR(flight_mode_channel, "FLTMODE_CH"),
|
||||
GSCALAR(flight_mode1, "FLTMODE1"),
|
||||
GSCALAR(flight_mode2, "FLTMODE2"),
|
||||
GSCALAR(flight_mode3, "FLTMODE3"),
|
||||
GSCALAR(flight_mode4, "FLTMODE4"),
|
||||
GSCALAR(flight_mode5, "FLTMODE5"),
|
||||
GSCALAR(flight_mode6, "FLTMODE6"),
|
||||
GSCALAR(flight_mode_channel, "FLTMODE_CH", FLIGHT_MODE_CHANNEL),
|
||||
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
|
||||
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
|
||||
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
|
||||
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
|
||||
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
|
||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||
|
||||
GSCALAR(roll_limit, "LIM_ROLL_CD"),
|
||||
GSCALAR(pitch_limit_max, "LIM_PITCH_MAX"),
|
||||
GSCALAR(pitch_limit_min, "LIM_PITCH_MIN"),
|
||||
GSCALAR(roll_limit, "LIM_ROLL_CD", HEAD_MAX_CENTIDEGREE),
|
||||
GSCALAR(pitch_limit_max, "LIM_PITCH_MAX", PITCH_MAX_CENTIDEGREE),
|
||||
GSCALAR(pitch_limit_min, "LIM_PITCH_MIN", PITCH_MIN_CENTIDEGREE),
|
||||
|
||||
GSCALAR(auto_trim, "TRIM_AUTO"),
|
||||
GSCALAR(switch_enable, "SWITCH_ENABLE"),
|
||||
GSCALAR(mix_mode, "ELEVON_MIXING"),
|
||||
GSCALAR(reverse_elevons, "ELEVON_REVERSE"),
|
||||
GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV"),
|
||||
GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV"),
|
||||
GSCALAR(num_resets, "SYS_NUM_RESETS"),
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK"),
|
||||
GSCALAR(log_last_filenumber, "LOG_LASTFILE"),
|
||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH"),
|
||||
GSCALAR(airspeed_cruise, "TRIM_ARSPD_CM"),
|
||||
GSCALAR(min_gndspeed, "MIN_GNDSPD_CM"),
|
||||
GSCALAR(ch7_option, "CH7_OPT"),
|
||||
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
|
||||
GSCALAR(switch_enable, "SWITCH_ENABLE", REVERSE_SWITCH),
|
||||
GSCALAR(mix_mode, "ELEVON_MIXING", ELEVON_MIXING),
|
||||
GSCALAR(reverse_elevons, "ELEVON_REVERSE", ELEVON_REVERSE),
|
||||
GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV", ELEVON_CH1_REVERSE),
|
||||
GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV", ELEVON_CH2_REVERSE),
|
||||
GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
GSCALAR(log_last_filenumber, "LOG_LASTFILE", 0),
|
||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
|
||||
GSCALAR(airspeed_cruise, "TRIM_ARSPD_CM", AIRSPEED_CRUISE_CM),
|
||||
GSCALAR(min_gndspeed, "MIN_GNDSPD_CM", MIN_GNDSPEED_CM),
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
GSCALAR(pitch_trim, "TRIM_PITCH_CD"),
|
||||
GSCALAR(RTL_altitude, "ALT_HOLD_RTL"),
|
||||
GSCALAR(FBWB_min_altitude, "ALT_HOLD_FBWCM"),
|
||||
GSCALAR(pitch_trim, "TRIM_PITCH_CD", 0),
|
||||
GSCALAR(RTL_altitude, "ALT_HOLD_RTL", ALT_HOLD_HOME_CM),
|
||||
GSCALAR(FBWB_min_altitude, "ALT_HOLD_FBWCM", ALT_HOLD_FBW_CM),
|
||||
|
||||
GSCALAR(ground_temperature, "GND_TEMP"),
|
||||
GSCALAR(ground_pressure, "GND_ABS_PRESS"),
|
||||
GSCALAR(compass_enabled, "MAG_ENABLE"),
|
||||
GSCALAR(flap_1_percent, "FLAP_1_PERCNT"),
|
||||
GSCALAR(flap_1_speed, "FLAP_1_SPEED"),
|
||||
GSCALAR(flap_2_percent, "FLAP_2_PERCNT"),
|
||||
GSCALAR(flap_2_speed, "FLAP_2_SPEED"),
|
||||
GSCALAR(ground_temperature, "GND_TEMP", 0),
|
||||
GSCALAR(ground_pressure, "GND_ABS_PRESS", 0),
|
||||
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
||||
GSCALAR(flap_1_percent, "FLAP_1_PERCNT", FLAP_1_PERCENT),
|
||||
GSCALAR(flap_1_speed, "FLAP_1_SPEED", FLAP_2_SPEED),
|
||||
GSCALAR(flap_2_percent, "FLAP_2_PERCNT", FLAP_2_PERCENT),
|
||||
GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED),
|
||||
|
||||
|
||||
GSCALAR(battery_monitoring, "BATT_MONITOR"),
|
||||
GSCALAR(volt_div_ratio, "VOLT_DIVIDER"),
|
||||
GSCALAR(curr_amp_per_volt, "AMP_PER_VOLT"),
|
||||
GSCALAR(input_voltage, "INPUT_VOLTS"),
|
||||
GSCALAR(pack_capacity, "BATT_CAPACITY"),
|
||||
GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH"),
|
||||
GSCALAR(battery_monitoring, "BATT_MONITOR", DISABLED),
|
||||
GSCALAR(volt_div_ratio, "VOLT_DIVIDER", VOLT_DIV_RATIO),
|
||||
GSCALAR(curr_amp_per_volt, "AMP_PER_VOLT", CURR_AMP_PER_VOLT),
|
||||
GSCALAR(input_voltage, "INPUT_VOLTS", INPUT_VOLTAGE),
|
||||
GSCALAR(pack_capacity, "BATT_CAPACITY", HIGH_DISCHARGE),
|
||||
GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH", 0),
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
// @Param: SONAR_ENABLE
|
||||
@ -111,20 +111,20 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: Setting this to Enabled(1) will enable the sonar. Setting this to Disabled(0) will disable the sonar
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_enabled, "SONAR_ENABLE"),
|
||||
GSCALAR(sonar_type, "SONAR_TYPE"),
|
||||
GSCALAR(sonar_enabled, "SONAR_ENABLE", SONAR_ENABLED),
|
||||
GSCALAR(sonar_type, "SONAR_TYPE", AP_RANGEFINDER_MAXSONARXL),
|
||||
#endif
|
||||
#endif
|
||||
GSCALAR(airspeed_enabled, "ARSPD_ENABLE"),
|
||||
GSCALAR(airspeed_enabled, "ARSPD_ENABLE", AIRSPEED_SENSOR),
|
||||
|
||||
// ************************************************************
|
||||
// APMrover parameters - JLN update
|
||||
|
||||
GSCALAR(closed_loop_nav, "ROV_CL_NAV"),
|
||||
GSCALAR(auto_wp_radius, "ROV_AWPR_NAV"),
|
||||
GSCALAR(sonar_trigger, "ROV_SONAR_TRIG"),
|
||||
GSCALAR(turn_gain, "ROV_GAIN"),
|
||||
GSCALAR(booster, "ROV_BOOSTER"),
|
||||
GSCALAR(closed_loop_nav, "ROV_CL_NAV", CLOSED_LOOP_NAV),
|
||||
GSCALAR(auto_wp_radius, "ROV_AWPR_NAV", AUTO_WP_RADIUS),
|
||||
GSCALAR(sonar_trigger, "ROV_SONAR_TRIG", SONAR_TRIGGER),
|
||||
GSCALAR(turn_gain, "ROV_GAIN", TURN_GAIN),
|
||||
GSCALAR(booster, "ROV_BOOSTER", BOOSTER),
|
||||
|
||||
// ************************************************************
|
||||
|
||||
@ -149,22 +149,14 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
|
||||
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
|
||||
GOBJECT(imu, "IMU_", IMU)
|
||||
GOBJECT(imu, "IMU_", IMU),
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
||||
static void load_parameters(void)
|
||||
{
|
||||
// setup the AP_Var subsystem for storage to EEPROM
|
||||
if (!AP_Param::setup(var_info, sizeof(var_info)/sizeof(var_info[0]), WP_START_BYTE)) {
|
||||
// this can only happen on startup, and its a definate coding
|
||||
// error. Best not to continue so the programmer catches it
|
||||
while (1) {
|
||||
Serial.println_P(PSTR("ERROR: Failed to setup AP_Param"));
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user