2012-04-30 04:17:14 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/*
ArduPlane parameter definitions
This firmware is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*/
2012-08-06 22:24:20 -03:00
#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} }
const AP_Param::Info var_info[] PROGMEM = {
2013-01-17 16:56:32 -04:00
GSCALAR(format_version, "FORMAT_VERSION", 1),
2012-08-06 22:24:20 -03:00
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),
2012-11-27 20:42:51 -04:00
2013-01-17 16:56:32 -04:00
// @Param: SERIAL0_BAUD
// @DisplayName: Telemetry Baud Rate
// @Description: The baud rate used on the first serial port
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
// @User: Standard
GSCALAR(serial0_baud, "SERIAL0_BAUD", SERIAL0_BAUD/1000),
2012-11-27 20:42:51 -04:00
// @Param: SERIAL3_BAUD
// @DisplayName: Telemetry Baud Rate
// @Description: The baud rate used on the telemetry port
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
2012-11-27 20:42:51 -04:00
// @Param: TELEM_DELAY
// @DisplayName: Telemetry startup delay
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
// @User: Standard
// @Units: seconds
// @Range: 0 10
// @Increment: 1
2012-08-29 20:36:18 -03:00
GSCALAR(telem_delay, "TELEM_DELAY", 0),
2012-11-27 20:42:51 -04:00
// @Param: MANUAL_LEVEL
// @DisplayName: Manual Level
2013-02-07 18:21:22 -04:00
// @Description: Setting this to Disabled(0) will enable autolevel on every boot. Setting it to Enabled(1) will do a calibration only when you tell it to. This defaults to enabled.
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
2013-02-07 18:21:22 -04:00
GSCALAR(manual_level, "MANUAL_LEVEL", 1),
2012-04-30 04:17:14 -03:00
2012-11-27 20:42:51 -04:00
// @Param: XTRK_GAIN_SC
// @DisplayName: Crosstrack Gain
2013-02-07 18:21:22 -04:00
// @Description: This controls how hard the Rover tries to follow the lines between waypoints, as opposed to driving directly to the next waypoint. The value is the scale between distance off the line and angle to meet the line (in Degrees * 100)
2012-11-27 20:42:51 -04:00
// @Range: 0 2000
// @Increment: 1
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", XTRACK_GAIN_SCALED),
2012-11-27 20:42:51 -04:00
// @Param: XTRK_ANGLE_CD
// @DisplayName: Crosstrack Entry Angle
// @Description: Maximum angle used to correct for track following.
// @Units: centi-Degrees
// @Range: 0 9000
// @Increment: 1
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD", XTRACK_ENTRY_ANGLE_CENTIDEGREE),
2012-04-30 04:17:14 -03:00
2012-08-06 22:24:20 -03:00
GSCALAR(command_total, "CMD_TOTAL", 0),
GSCALAR(command_index, "CMD_INDEX", 0),
2013-02-07 18:21:22 -04:00
// @Param: WP_RADIUS
// @DisplayName: Waypoint radius
// @Description: The distance in meters from a waypoint when we consider the waypoint has been reached. This determines when the rover will turn along the next waypoint path.
// @Units: meters
// @Range: 0 1000
// @Increment: 0.1
// @User: Standard
GSCALAR(waypoint_radius, "WP_RADIUS", 2.0f),
2012-04-30 04:17:14 -03:00
2012-11-27 20:42:51 -04:00
// @Param: THR_MIN
// @DisplayName: Minimum Throttle
2013-02-07 18:21:22 -04:00
// @Description: The minimum throttle setting to which the autopilot will apply. This is mostly useful for rovers with internal combustion motors, to prevent the motor from cutting out in auto mode.
2012-11-27 20:42:51 -04:00
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
2012-11-27 20:42:51 -04:00
// @Param: THR_MAX
// @DisplayName: Maximum Throttle
// @Description: The maximum throttle setting to which the autopilot will apply.
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
2012-11-27 20:42:51 -04:00
// @Param: THR_SLEWRATE
2012-12-03 20:38:29 -04:00
// @DisplayName: Throttle slew rate
2012-11-27 20:42:51 -04:00
// @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(throttle_slewrate, "THR_SLEWRATE", 0),
2012-11-27 20:42:51 -04:00
// @Param: THR_FAILSAFE
// @DisplayName: Throttle Failsafe Enable
2013-02-07 18:21:22 -04:00
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel to a low value. This can be used to detect the RC transmitter going out of range.
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", THROTTLE_FAILSAFE),
2012-11-27 20:42:51 -04:00
// @Param: THR_FS_VALUE
// @DisplayName: Throttle Failsafe Value
2013-02-07 18:21:22 -04:00
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers.
2012-11-27 20:42:51 -04:00
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR(throttle_fs_value, "THR_FS_VALUE", THROTTLE_FS_VALUE),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: CRUISE_THROTTLE
2012-11-27 20:42:51 -04:00
// @DisplayName: Throttle cruise percentage
2013-02-07 18:21:22 -04:00
// @Description: The target percentage of throttle to apply for auto missions.
2012-11-27 20:42:51 -04:00
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(throttle_cruise, "CRUISE_THROTTLE", 50),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: CRUISE_SPEED
// @DisplayName: Target speed in auto modes
// @Description: The target speed in auto missions.
// @Units: m/s
// @Range: 0 100
// @Increment: 0.1
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(speed_cruise, "CRUISE_SPEED", 5),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: FS_GCS_ENABLE
2012-11-27 20:42:51 -04:00
// @DisplayName: GCS failsafe enable
2013-02-07 18:21:22 -04:00
// @Description: Enable ground control station telemetry failsafe
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABLE", 0),
2012-08-06 22:24:20 -03:00
2013-02-07 18:21:22 -04:00
// @Param: MODE_CH
// @DisplayName: Mode channel
2012-11-27 20:42:51 -04:00
// @Description: RC Channel to use for flight mode control
// @User: Advanced
2013-02-07 18:21:22 -04:00
GSCALAR(mode_channel, "MODE_CH", MODE_CHANNEL),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE1
// @DisplayName: Mode1
// @Values: 0:Manual,2:LEARNING,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)
2013-02-07 18:21:22 -04:00
GSCALAR(mode1, "MODE1", MODE_1),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE2
// @DisplayName: Mode2
2012-11-27 20:42:51 -04:00
// @Description: Flight mode for switch position 2 (1231 to 1360)
2013-02-07 18:21:22 -04:00
// @Values: 0:Manual,2:LEARNING,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(mode2, "MODE2", MODE_2),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE3
// @DisplayName: Mode3
2012-11-27 20:42:51 -04:00
// @Description: Flight mode for switch position 3 (1361 to 1490)
2013-02-07 18:21:22 -04:00
// @Values: 0:Manual,2:LEARNING,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(mode3, "MODE3", MODE_3),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE4
// @DisplayName: Mode4
2012-11-27 20:42:51 -04:00
// @Description: Flight mode for switch position 4 (1491 to 1620)
2013-02-07 18:21:22 -04:00
// @Values: 0:Manual,2:LEARNING,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(mode4, "MODE4", MODE_4),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE5
// @DisplayName: Mode5
2012-11-27 20:42:51 -04:00
// @Description: Flight mode for switch position 5 (1621 to 1749)
2013-02-07 18:21:22 -04:00
// @Values: 0:Manual,2:LEARNING,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(mode5, "MODE5", MODE_5),
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE6
// @DisplayName: Mode6
2012-11-27 20:42:51 -04:00
// @Description: Flight mode for switch position 6 (1750 to 2049)
2013-02-07 18:21:22 -04:00
// @Values: 0:Manual,2:LEARNING,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR(mode6, "MODE6", MODE_6),
2012-08-06 22:24:20 -03:00
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(ch7_option, "CH7_OPT", CH7_OPTION),
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
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),
2012-12-18 07:44:12 -04:00
// @Param: BATT_VOLT_PIN
// @DisplayName: Battery Voltage sensing pin
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13.
// @Values: -1:Disabled, 0:A0, 1:A1, 13:A13
// @User: Standard
GSCALAR(battery_volt_pin, "BATT_VOLT_PIN", 1),
// @Param: BATT_CURR_PIN
// @DisplayName: Battery Current sensing pin
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13.
// @Values: -1:Disabled, 1:A1, 2:A2, 12:A12
// @User: Standard
GSCALAR(battery_curr_pin, "BATT_CURR_PIN", 2),
// @Param: RSSI_PIN
// @DisplayName: Receiver RSSI sensing pin
// @Description: This selects an analog pin for the receiver RSSI voltage. It assumes the voltage is 5V for max rssi, 0V for minimum
// @Values: -1:Disabled, 0:A0, 1:A1, 13:A13
// @User: Standard
GSCALAR(rssi_pin, "RSSI_PIN", -1),
2012-05-14 12:47:08 -03:00
#if HIL_MODE != HIL_MODE_ATTITUDE
2012-06-13 03:29:32 -03:00
#if CONFIG_SONAR == ENABLED
2012-05-14 12:47:08 -03:00
// @Param: SONAR_ENABLE
// @DisplayName: Enable Sonar
// @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
2012-08-06 22:24:20 -03:00
GSCALAR(sonar_enabled, "SONAR_ENABLE", SONAR_ENABLED),
GSCALAR(sonar_type, "SONAR_TYPE", AP_RANGEFINDER_MAXSONARXL),
2012-05-14 12:47:08 -03:00
#endif
#endif
2012-04-30 04:17:14 -03:00
// ************************************************************
// APMrover parameters - JLN update
2012-08-06 22:24:20 -03:00
GSCALAR(sonar_trigger, "ROV_SONAR_TRIG", SONAR_TRIGGER),
GSCALAR(booster, "ROV_BOOSTER", BOOSTER),
2012-05-17 13:42:16 -03:00
2012-04-30 04:17:14 -03:00
// ************************************************************
2013-02-07 18:21:22 -04:00
GGROUP(channel_steer, "RC1_", RC_Channel),
GGROUP(rc_2, "RC2_", RC_Channel_aux),
2012-04-30 04:17:14 -03:00
GGROUP(channel_throttle, "RC3_", RC_Channel),
2013-02-07 18:21:22 -04:00
GGROUP(rc_4, "RC4_", RC_Channel_aux),
2012-04-30 04:17:14 -03:00
GGROUP(rc_5, "RC5_", RC_Channel_aux),
GGROUP(rc_6, "RC6_", RC_Channel_aux),
GGROUP(rc_7, "RC7_", RC_Channel_aux),
GGROUP(rc_8, "RC8_", RC_Channel_aux),
2013-02-07 18:21:22 -04:00
GGROUP(pidNavSteer, "HDNG2STEER_", PID),
GGROUP(pidServoSteer, "STEER2SRV_", PID),
GGROUP(pidSpeedThrottle, "SPEED2THR_", PID),
2012-04-30 04:17:14 -03:00
// variables not in the g class which contain EEPROM saved variables
GOBJECT(compass, "COMPASS_", Compass),
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
2012-11-07 03:28:20 -04:00
#if HIL_MODE == HIL_MODE_DISABLED
// @Group: INS_
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
GOBJECT(ins, "INS_", AP_InertialSensor),
#endif
2012-08-06 22:24:20 -03:00
2012-12-18 07:44:12 -04:00
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
2012-11-27 08:20:25 -04:00
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp
GOBJECT(sitl, "SIM_", SITL),
#endif
2012-11-17 02:45:20 -04:00
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),
2012-08-06 22:24:20 -03:00
AP_VAREND
2012-04-30 04:17:14 -03:00
};
static void load_parameters(void)
{
if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
// erase all parameters
2012-11-21 02:25:11 -04:00
cliSerial->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
2012-04-30 04:17:14 -03:00
AP_Param::erase_all();
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
2012-11-21 02:25:11 -04:00
cliSerial->println_P(PSTR("done."));
2012-04-30 04:17:14 -03:00
} else {
unsigned long before = micros();
// Load all auto-loaded EEPROM variables
AP_Param::load_all();
2012-11-21 02:25:11 -04:00
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
2012-04-30 04:17:14 -03:00
}
}