mirror of https://github.com/ArduPilot/ardupilot
1107 lines
47 KiB
Plaintext
1107 lines
47 KiB
Plaintext
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
/*
|
|
This program is free software: you can redistribute it and/or modify
|
|
it under the terms of the GNU General Public License as published by
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
(at your option) any later version.
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
GNU General Public License for more details.
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
|
|
/*
|
|
* ArduCopter parameter definitions
|
|
*
|
|
*/
|
|
|
|
#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 = {
|
|
// @Param: SYSID_SW_MREV
|
|
// @DisplayName: Eeprom format version number
|
|
// @Description: This value is incremented when changes are made to the eeprom format
|
|
// @User: Advanced
|
|
GSCALAR(format_version, "SYSID_SW_MREV", 0),
|
|
|
|
// @Param: SYSID_SW_TYPE
|
|
// @DisplayName: Software Type
|
|
// @Description: This is used by the ground station to recognise the software type (eg ArduPlane vs ArduCopter)
|
|
// @User: Advanced
|
|
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
|
|
|
|
// @Param: SYSID_THISMAV
|
|
// @DisplayName: Mavlink version
|
|
// @Description: Allows reconising the mavlink version
|
|
// @User: Advanced
|
|
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
|
|
|
// @Param: SYSID_MYGCS
|
|
// @DisplayName: My ground station number
|
|
// @Description: Allows restricting radio overrides to only come from my ground station
|
|
// @User: Advanced
|
|
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
|
|
|
// @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
|
|
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
|
|
|
|
// @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
|
|
GSCALAR(telem_delay, "TELEM_DELAY", 0),
|
|
|
|
// @Param: RTL_ALT
|
|
// @DisplayName: RTL Altitude
|
|
// @Description: The minimum altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
|
|
// @Units: Centimeters
|
|
// @Range: 0 8000
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),
|
|
|
|
// @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
|
|
GSCALAR(sonar_enabled, "SONAR_ENABLE", DISABLED),
|
|
|
|
// @Param: SONAR_TYPE
|
|
// @DisplayName: Sonar type
|
|
// @Description: Used to adjust scaling to match the sonar used (only Maxbotix sonars are supported at this time)
|
|
// @Values: 0:XL-EZ0 / XL-EZ4,1:LV-EZ0,2:XLL-EZ0,3:HRLV
|
|
// @User: Standard
|
|
GSCALAR(sonar_type, "SONAR_TYPE", AP_RANGEFINDER_MAXSONARXL),
|
|
|
|
// @Param: SONAR_GAIN
|
|
// @DisplayName: Sonar gain
|
|
// @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter
|
|
// @Range: 0.01 0.5
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
GSCALAR(sonar_gain, "SONAR_GAIN", SONAR_GAIN_DEFAULT),
|
|
|
|
// @Param: BATT_MONITOR
|
|
// @DisplayName: Battery monitoring
|
|
// @Description: Controls enabling monitoring of the battery's voltage and current
|
|
// @Values: 0:Disabled,3:Voltage Only,4:Voltage and Current
|
|
// @User: Standard
|
|
GSCALAR(battery_monitoring, "BATT_MONITOR", BATT_MONITOR_DISABLED),
|
|
|
|
// @Param: FS_BATT_ENABLE
|
|
// @DisplayName: Battery Failsafe Enable
|
|
// @Description: Controls whether failsafe will be invoked when battery voltage or current runs low
|
|
// @Values: 0:Disabled,1:Enabled
|
|
// @User: Standard
|
|
GSCALAR(failsafe_battery_enabled, "FS_BATT_ENABLE", FS_BATTERY),
|
|
|
|
// @Param: FS_GPS_ENABLE
|
|
// @DisplayName: GPS Failsafe Enable
|
|
// @Description: Controls whether failsafe will be invoked when gps signal is lost
|
|
// @Values: 0:Disabled,1:Enabled
|
|
// @User: Standard
|
|
GSCALAR(failsafe_gps_enabled, "FS_GPS_ENABLE", FS_GPS),
|
|
|
|
// @Param: FS_GCS_ENABLE
|
|
// @DisplayName: Ground Station Failsafe Enable
|
|
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds
|
|
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode
|
|
// @User: Standard
|
|
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),
|
|
|
|
// @Param: GPS_HDOP_GOOD
|
|
// @DisplayName: GPS Hdop Good
|
|
// @Description: GPS Hdop value below which represent a good position. Used for pre-arm checks
|
|
// @Range: 100 900
|
|
// @User: Advanced
|
|
GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),
|
|
|
|
// @Param: VOLT_DIVIDER
|
|
// @DisplayName: Voltage Divider
|
|
// @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_DIVIDER). For the 3DR Power brick on APM2 or Pixhawk this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1.
|
|
// @User: Advanced
|
|
GSCALAR(volt_div_ratio, "VOLT_DIVIDER", VOLT_DIV_RATIO),
|
|
|
|
// @Param: AMP_PER_VOLT
|
|
// @DisplayName: Current Amps per volt
|
|
// @Description: Used to convert the voltage on the current sensing pin (BATT_CURR_PIN) to the actual current being consumed in amps. For the 3DR Power brick on APM2 or Pixhawk it should be set to 17.
|
|
// @User: Advanced
|
|
GSCALAR(curr_amp_per_volt, "AMP_PER_VOLT", CURR_AMP_PER_VOLT),
|
|
|
|
// @Param: BATT_CAPACITY
|
|
// @DisplayName: Battery Capacity
|
|
// @Description: Battery capacity in milliamp-hours (mAh)
|
|
// @Units: mAh
|
|
// @User: Standard
|
|
GSCALAR(pack_capacity, "BATT_CAPACITY", BATTERY_CAPACITY_DEFAULT),
|
|
|
|
// @Param: MAG_ENABLE
|
|
// @DisplayName: Enable Compass
|
|
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass
|
|
// @Values: 0:Disabled,1:Enabled
|
|
// @User: Standard
|
|
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
|
|
|
// @Param: FLOW_ENABLE
|
|
// @DisplayName: Enable Optical Flow
|
|
// @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow
|
|
// @Values: 0:Disabled,1:Enabled
|
|
// @User: Standard
|
|
GSCALAR(optflow_enabled, "FLOW_ENABLE", DISABLED),
|
|
|
|
// @Param: LOW_VOLT
|
|
// @DisplayName: Low Voltage
|
|
// @Description: Set this to the voltage you want to represent low voltage
|
|
// @Range: 0 20
|
|
// @Increment: 0.1
|
|
// @User: Standard
|
|
GSCALAR(low_voltage, "LOW_VOLT", LOW_VOLTAGE),
|
|
|
|
// @Param: SUPER_SIMPLE
|
|
// @DisplayName: Enable Super Simple Mode
|
|
// @Description: Setting this to Enabled(1) will enable Super Simple Mode. Setting this to Disabled(0) will disable Super Simple Mode
|
|
// @Values: 0:Disabled,1:Enabled
|
|
// @User: Standard
|
|
GSCALAR(super_simple, "SUPER_SIMPLE", SUPER_SIMPLE),
|
|
|
|
// @Param: RTL_ALT_FINAL
|
|
// @DisplayName: RTL Final Altitude
|
|
// @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.
|
|
// @Units: Centimeters
|
|
// @Range: -1 1000
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(rtl_alt_final, "RTL_ALT_FINAL", RTL_ALT_FINAL),
|
|
|
|
// @Param: BATT_VOLT_PIN
|
|
// @DisplayName: Battery Voltage sensing pin
|
|
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 13. On the PX4 it should be set to 100. On the Pixhawk powered from the PM connector it should be set to 2.
|
|
// @Values: -1:Disabled, 0:A0, 1:A1, 2:Pixhawk, 13:A13, 100:PX4
|
|
// @User: Standard
|
|
GSCALAR(battery_volt_pin, "BATT_VOLT_PIN", BATTERY_VOLT_PIN),
|
|
|
|
// @Param: BATT_CURR_PIN
|
|
// @DisplayName: Battery Current sensing pin
|
|
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13. For the 3DR power brick on APM2.5 it should be set to 12. On the PX4 it should be set to 101. On the Pixhawk powered from the PM connector it should be set to 3.
|
|
// @Values: -1:Disabled, 1:A1, 2:A2, 3:Pixhawk, 12:A12, 101:PX4
|
|
// @User: Standard
|
|
GSCALAR(battery_curr_pin, "BATT_CURR_PIN", BATTERY_CURR_PIN),
|
|
|
|
// @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, 2:A2, 13:A13
|
|
// @User: Standard
|
|
GSCALAR(rssi_pin, "RSSI_PIN", -1),
|
|
|
|
// @Param: WP_YAW_BEHAVIOR
|
|
// @DisplayName: Yaw behaviour during missions
|
|
// @Description: Determines how the autopilot controls the yaw during missions and RTL
|
|
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course
|
|
// @User: Advanced
|
|
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
|
|
|
|
// @Param: WP_TOTAL
|
|
// @DisplayName: Waypoint Total
|
|
// @Description: Total number of commands in the mission stored in the eeprom. Do not update this parameter directly!
|
|
// @User: Advanced
|
|
GSCALAR(command_total, "WP_TOTAL", 0),
|
|
|
|
// @Param: WP_INDEX
|
|
// @DisplayName: Waypoint Index
|
|
// @Description: The index number of the command that is currently being executed. Do not update this parameter directly!
|
|
// @User: Advanced
|
|
GSCALAR(command_index, "WP_INDEX", 0),
|
|
|
|
// @Param: CIRCLE_RADIUS
|
|
// @DisplayName: Circle radius
|
|
// @Description: Defines the radius of the circle the vehicle will fly when in Circle flight mode
|
|
// @Units: Meters
|
|
// @Range: 1 127
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(circle_radius, "CIRCLE_RADIUS", CIRCLE_RADIUS),
|
|
|
|
// @Param: CIRCLE_RATE
|
|
// @DisplayName: Circle rate
|
|
// @Description: Circle mode's turn rate in degrees / second. Positive to turn clockwise, negative for counter clockwise
|
|
// @Units: deg/s
|
|
// @Range: -90 90
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(circle_rate, "CIRCLE_RATE", CIRCLE_RATE),
|
|
|
|
// @Param: RTL_LOIT_TIME
|
|
// @DisplayName: RTL loiter time
|
|
// @Description: Time (in milliseconds) to loiter above home before begining final descent
|
|
// @Units: ms
|
|
// @Range: 0 60000
|
|
// @Increment: 1000
|
|
// @User: Standard
|
|
GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),
|
|
|
|
// @Param: LAND_SPEED
|
|
// @DisplayName: Land speed
|
|
// @Description: The descent speed for the final stage of landing in cm/s
|
|
// @Units: cm/s
|
|
// @Range: 20 200
|
|
// @Increment: 10
|
|
// @User: Standard
|
|
GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),
|
|
|
|
// @Param: PILOT_VELZ_MAX
|
|
// @DisplayName: Pilot maximum vertical speed
|
|
// @Description: The maximum vertical velocity the pilot may request in cm/s
|
|
// @Units: Centimeters/Second
|
|
// @Range: 10 500
|
|
// @Increment: 10
|
|
// @User: Standard
|
|
GSCALAR(pilot_velocity_z_max, "PILOT_VELZ_MAX", PILOT_VELZ_MAX),
|
|
|
|
// @Param: THR_MIN
|
|
// @DisplayName: Minimum Throttle
|
|
// @Description: The minimum throttle that will be sent to the motors to keep them spinning
|
|
// @Units: ms
|
|
// @Range: 0 300
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(throttle_min, "THR_MIN", MINIMUM_THROTTLE),
|
|
|
|
// @Param: THR_MAX
|
|
// @DisplayName: Maximum Throttle
|
|
// @Description: The maximum throttle that will be sent to the motors
|
|
// @Units: ms
|
|
// @Range: 0 1000
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(throttle_max, "THR_MAX", MAXIMUM_THROTTLE),
|
|
|
|
// @Param: FS_THR_ENABLE
|
|
// @DisplayName: Throttle Failsafe Enable
|
|
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
|
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always LAND
|
|
// @User: Standard
|
|
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_DISABLED),
|
|
|
|
// @Param: FS_THR_VALUE
|
|
// @DisplayName: Throttle Failsafe Value
|
|
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers
|
|
// @Range: 925 1100
|
|
// @Units: ms
|
|
// @Increment: 1
|
|
// @User: Standard
|
|
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
|
|
|
|
// @Param: TRIM_THROTTLE
|
|
// @DisplayName: Throttle Trim
|
|
// @Description: The autopilot's estimate of the throttle required to maintain a level hover. Calculated automatically from the pilot's throttle input while in stabilize mode
|
|
// @Range: 0 1000
|
|
// @Units: ms
|
|
// @User: Standard
|
|
GSCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
|
|
|
|
// @Param: THR_MID
|
|
// @DisplayName: Throttle Mid Position
|
|
// @Description: The throttle output (0 ~ 1000) when throttle stick is in mid position. Used to scale the manual throttle so that the mid throttle stick position is close to the throttle required to hover
|
|
// @User: Standard
|
|
// @Range: 300 700
|
|
// @Increment: 1
|
|
GSCALAR(throttle_mid, "THR_MID", THR_MID),
|
|
|
|
// @Param: FLTMODE1
|
|
// @DisplayName: Flight Mode 1
|
|
// @Description: Flight mode when Channel 5 pwm is <= 1230
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
|
|
// @User: Standard
|
|
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
|
|
|
|
// @Param: FLTMODE2
|
|
// @DisplayName: Flight Mode 2
|
|
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
|
|
// @User: Standard
|
|
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
|
|
|
|
// @Param: FLTMODE3
|
|
// @DisplayName: Flight Mode 3
|
|
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
|
|
// @User: Standard
|
|
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
|
|
|
|
// @Param: FLTMODE4
|
|
// @DisplayName: Flight Mode 4
|
|
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
|
|
// @User: Standard
|
|
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
|
|
|
|
// @Param: FLTMODE5
|
|
// @DisplayName: Flight Mode 5
|
|
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
|
|
// @User: Standard
|
|
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
|
|
|
|
// @Param: FLTMODE6
|
|
// @DisplayName: Flight Mode 6
|
|
// @Description: Flight mode when Channel 5 pwm is >=1750
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
|
|
// @User: Standard
|
|
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
|
|
|
// @Param: SIMPLE
|
|
// @DisplayName: Simple mode bitmask
|
|
// @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode)
|
|
// @User: Advanced
|
|
GSCALAR(simple_modes, "SIMPLE", 0),
|
|
|
|
// @Param: LOG_BITMASK
|
|
// @DisplayName: Log bitmask
|
|
// @Description: 2 byte bitmap of log types to enable
|
|
// @Values: 0:Disabled,830:Default,958:Default+IMU,1854:Default+Motors,17214:Default+INav
|
|
// @User: Advanced
|
|
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
|
|
|
// @Param: TOY_RATE
|
|
// @DisplayName: Toy Yaw Rate
|
|
// @Description: Controls yaw rate in Toy mode. Higher values will cause a slower yaw rate. Do not set to zero!
|
|
// @User: Advanced
|
|
// @Range: 1 10
|
|
GSCALAR(toy_yaw_rate, "TOY_RATE", 1),
|
|
|
|
// @Param: ESC
|
|
// @DisplayName: ESC Calibration
|
|
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
|
|
// @User: Advanced
|
|
// @Values: 0:Normal Start-up,1:Start-up in ESC Calibration mode
|
|
GSCALAR(esc_calibrate, "ESC", 0),
|
|
|
|
// @Param: TUNE
|
|
// @DisplayName: Channel 6 Tuning
|
|
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
|
|
// @User: Standard
|
|
// @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,14:Altitude Hold kP,7:Throttle Rate kP,37:Throttle Rate kD,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Loiter Rate kP,28:Loiter Rate kI,23:Loiter Rate kD,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,9:Relay On/Off,13:Heli Ext Gyro,17:OF Loiter kP,18:OF Loiter kI,19:OF Loiter kD,30:AHRS Yaw kP,31:AHRS kP,32:INAV_TC,38:Declination,39:Circle Rate,41:Sonar Gain
|
|
GSCALAR(radio_tuning, "TUNE", 0),
|
|
|
|
// @Param: TUNE_LOW
|
|
// @DisplayName: Tuning minimum
|
|
// @Description: The minimum value that will be applied to the parameter currently being tuned with the transmitter's channel 6 knob
|
|
// @User: Standard
|
|
// @Range: 0 32767
|
|
GSCALAR(radio_tuning_low, "TUNE_LOW", 0),
|
|
|
|
// @Param: TUNE_HIGH
|
|
// @DisplayName: Tuning maximum
|
|
// @Description: The maximum value that will be applied to the parameter currently being tuned with the transmitter's channel 6 knob
|
|
// @User: Standard
|
|
// @Range: 0 32767
|
|
GSCALAR(radio_tuning_high, "TUNE_HIGH", 1000),
|
|
|
|
// @Param: FRAME
|
|
// @DisplayName: Frame Orientation (+, X or V)
|
|
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
|
|
// @Values: 0:Plus, 1:X, 2:V, 3:H
|
|
// @User: Standard
|
|
GSCALAR(frame_orientation, "FRAME", FRAME_ORIENTATION),
|
|
|
|
// @Param: CH7_OPT
|
|
// @DisplayName: Channel 7 option
|
|
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto
|
|
// @User: Standard
|
|
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
|
|
|
// @Param: CH8_OPT
|
|
// @DisplayName: Channel 8 option
|
|
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto
|
|
// @User: Standard
|
|
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
|
|
|
// @Param: ARMING_CHECK
|
|
// @DisplayName: Arming check
|
|
// @Description: Allows enabling or disabling of pre-arming checks of receiver, accelerometer, barometer and compass
|
|
// @Values: 0:Disabled, 1:Enabled
|
|
// @User: Standard
|
|
GSCALAR(arming_check_enabled, "ARMING_CHECK", 1),
|
|
|
|
// @Param: ANGLE_MAX
|
|
// @DisplayName: Angle Max
|
|
// @Description: Maximum lean angle in all flight modes
|
|
// @Range 1000 8000
|
|
// @User: Advanced
|
|
GSCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
// @Group: HS1_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(heli_servo_1, "HS1_", RC_Channel),
|
|
// @Group: HS2_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(heli_servo_2, "HS2_", RC_Channel),
|
|
// @Group: HS3_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(heli_servo_3, "HS3_", RC_Channel),
|
|
// @Group: HS4_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(heli_servo_4, "HS4_", RC_Channel),
|
|
|
|
// @Param: RATE_PIT_FF
|
|
// @DisplayName: Rate Pitch Feed Forward
|
|
// @Description: Rate Pitch Feed Forward (for TradHeli Only)
|
|
// @Range: 0 10
|
|
// @User: Standard
|
|
GSCALAR(heli_pitch_ff, "RATE_PIT_FF", HELI_PITCH_FF),
|
|
|
|
// @Param: RATE_RLL_FF
|
|
// @DisplayName: Rate Roll Feed Forward
|
|
// @Description: Rate Roll Feed Forward (for TradHeli Only)
|
|
// @Range: 0 10
|
|
// @User: Standard
|
|
GSCALAR(heli_roll_ff, "RATE_RLL_FF", HELI_ROLL_FF),
|
|
|
|
// @Param: RATE_YAW_FF
|
|
// @DisplayName: Rate Yaw Feed Forward
|
|
// @Description: Rate Yaw Feed Forward (for TradHeli Only)
|
|
// @Range: 0 10
|
|
// @User: Standard
|
|
GSCALAR(heli_yaw_ff, "RATE_YAW_FF", HELI_YAW_FF),
|
|
#endif
|
|
|
|
// RC channel
|
|
//-----------
|
|
// @Group: RC1_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(rc_1, "RC1_", RC_Channel),
|
|
// @Group: RC2_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(rc_2, "RC2_", RC_Channel),
|
|
// @Group: RC3_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(rc_3, "RC3_", RC_Channel),
|
|
// @Group: RC4_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
|
GGROUP(rc_4, "RC4_", RC_Channel),
|
|
// @Group: RC5_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_5, "RC5_", RC_Channel_aux),
|
|
// @Group: RC6_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_6, "RC6_", RC_Channel_aux),
|
|
// @Group: RC7_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_7, "RC7_", RC_Channel_aux),
|
|
// @Group: RC8_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
|
|
|
#if MOUNT == ENABLED
|
|
// @Group: RC10_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_10, "RC10_", RC_Channel_aux),
|
|
|
|
// @Group: RC11_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
|
#endif
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
// @Group: RC9_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
|
// @Group: RC12_
|
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
|
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
|
#endif
|
|
|
|
// @Param: RC_SPEED
|
|
// @DisplayName: ESC Update Speed
|
|
// @Description: This is the speed in Hertz that your ESCs will receive updates
|
|
// @Units: Hz
|
|
// @Range: 50 490
|
|
// @Increment: 1
|
|
// @User: Advanced
|
|
GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),
|
|
|
|
// @Param: ACRO_RP_P
|
|
// @DisplayName: Acro Roll and Pitch P gain
|
|
// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
|
|
// @Range: 1 10
|
|
// @User: Standard
|
|
GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P),
|
|
|
|
// @Param: ACRO_YAW_P
|
|
// @DisplayName: Acro Yaw P gain
|
|
// @Description: Converts pilot yaw input into a desired rate of rotation in ACRO, Stabilize and SPORT modes. Higher values mean faster rate of rotation.
|
|
// @Range: 1 10
|
|
// @User: Standard
|
|
GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
|
|
|
|
// @Param: ACRO_BAL_ROLL
|
|
// @DisplayName: Acro Balance Roll
|
|
// @Description: rate at which roll angle returns to level in acro mode
|
|
// @Range: 0 3
|
|
// @Increment: 0.1
|
|
// @User: Advanced
|
|
GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),
|
|
|
|
// @Param: ACRO_BAL_PITCH
|
|
// @DisplayName: Acro Balance Pitch
|
|
// @Description: rate at which pitch angle returns to level in acro mode
|
|
// @Range: 0 3
|
|
// @Increment: 0.1
|
|
// @User: Advanced
|
|
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
|
|
|
|
// @Param: ACRO_TRAINER
|
|
// @DisplayName: Acro Trainer
|
|
// @Description: Type of trainer used in acro mode
|
|
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
|
|
// @User: Advanced
|
|
GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),
|
|
|
|
// @Param: LED_MODE
|
|
// @DisplayName: Copter LED Mode
|
|
// @Description: bitmap to control the copter led mode
|
|
// @Values: 0:Disabled,1:Enable,3:GPS On,4:Aux,9:Buzzer,17:Oscillate,33:Nav Blink,65:GPS Nav Blink
|
|
// @User: Standard
|
|
GSCALAR(copter_leds_mode, "LED_MODE", 9),
|
|
|
|
// PID controller
|
|
//---------------
|
|
// @Param: RATE_RLL_P
|
|
// @DisplayName: Roll axis rate controller P gain
|
|
// @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
|
|
// @Range: 0.08 0.20
|
|
// @Increment: 0.005
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_RLL_I
|
|
// @DisplayName: Roll axis rate controller I gain
|
|
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
|
|
// @Range: 0.01 0.5
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_RLL_IMAX
|
|
// @DisplayName: Roll axis rate controller I gain maximum
|
|
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
|
// @Range: 0 500
|
|
// @Increment: 10
|
|
// @Units: ms
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_RLL_D
|
|
// @DisplayName: Roll axis rate controller D gain
|
|
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
|
|
// @Range: 0.001 0.008
|
|
// @Increment: 0.001
|
|
// @User: Standard
|
|
GGROUP(pid_rate_roll, "RATE_RLL_", AC_PID),
|
|
|
|
// @Param: RATE_PIT_P
|
|
// @DisplayName: Pitch axis rate controller P gain
|
|
// @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
|
|
// @Range: 0.08 0.20
|
|
// @Increment: 0.005
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_PIT_I
|
|
// @DisplayName: Pitch axis rate controller I gain
|
|
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
|
|
// @Range: 0.01 0.5
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_PIT_IMAX
|
|
// @DisplayName: Pitch axis rate controller I gain maximum
|
|
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
|
// @Range: 0 500
|
|
// @Increment: 10
|
|
// @Units: ms
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_PIT_D
|
|
// @DisplayName: Pitch axis rate controller D gain
|
|
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
|
|
// @Range: 0.001 0.008
|
|
// @Increment: 0.001
|
|
// @User: Standard
|
|
GGROUP(pid_rate_pitch, "RATE_PIT_", AC_PID),
|
|
|
|
// @Param: RATE_YAW_P
|
|
// @DisplayName: Yaw axis rate controller P gain
|
|
// @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
|
|
// @Range: 0.150 0.250
|
|
// @Increment: 0.005
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_YAW_I
|
|
// @DisplayName: Yaw axis rate controller I gain
|
|
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
|
|
// @Range: 0.010 0.020
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_YAW_IMAX
|
|
// @DisplayName: Yaw axis rate controller I gain maximum
|
|
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
|
// @Range: 0 500
|
|
// @Increment: 10
|
|
// @Units: ms
|
|
// @User: Standard
|
|
|
|
// @Param: RATE_YAW_D
|
|
// @DisplayName: Yaw axis rate controller D gain
|
|
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
|
|
// @Range: 0.000 0.001
|
|
// @Increment: 0.001
|
|
// @User: Standard
|
|
GGROUP(pid_rate_yaw, "RATE_YAW_", AC_PID),
|
|
|
|
// @Param: LOITER_LAT_P
|
|
// @DisplayName: Loiter latitude rate controller P gain
|
|
// @Description: Loiter latitude rate controller P gain. Converts the difference between desired speed and actual speed into a lean angle in the latitude direction
|
|
// @Range: 0.1 6.0
|
|
// @Increment: 0.1
|
|
// @User: Standard
|
|
|
|
// @Param: LOITER_LAT_I
|
|
// @DisplayName: Loiter latitude rate controller I gain
|
|
// @Description: Loiter latitude rate controller I gain. Corrects long-term difference in desired speed and actual speed in the latitude direction
|
|
// @Range: 0.02 1.00
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: LOITER_LAT_IMAX
|
|
// @DisplayName: Loiter rate controller I gain maximum
|
|
// @Description: Loiter rate controller I gain maximum. Constrains the lean angle that the I gain will output
|
|
// @Range: 0 4500
|
|
// @Increment: 10
|
|
// @Units: Centi-Degrees
|
|
// @User: Standard
|
|
|
|
// @Param: LOITER_LAT_D
|
|
// @DisplayName: Loiter latitude rate controller D gain
|
|
// @Description: Loiter latitude rate controller D gain. Compensates for short-term change in desired speed vs actual speed
|
|
// @Range: 0.0 0.6
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
GGROUP(pid_loiter_rate_lat, "LOITER_LAT_", AC_PID),
|
|
|
|
// @Param: LOITER_LON_P
|
|
// @DisplayName: Loiter longitude rate controller P gain
|
|
// @Description: Loiter longitude rate controller P gain. Converts the difference between desired speed and actual speed into a lean angle in the longitude direction
|
|
// @Range: 0.1 6.0
|
|
// @Increment: 0.1
|
|
// @User: Standard
|
|
|
|
// @Param: LOITER_LON_I
|
|
// @DisplayName: Loiter longitude rate controller I gain
|
|
// @Description: Loiter longitude rate controller I gain. Corrects long-term difference in desired speed and actual speed in the longitude direction
|
|
// @Range: 0.02 1.00
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: LOITER_LON_IMAX
|
|
// @DisplayName: Loiter longitude rate controller I gain maximum
|
|
// @Description: Loiter longitude rate controller I gain maximum. Constrains the lean angle that the I gain will output
|
|
// @Range: 0 4500
|
|
// @Increment: 10
|
|
// @Units: Centi-Degrees
|
|
// @User: Standard
|
|
|
|
// @Param: LOITER_LON_D
|
|
// @DisplayName: Loiter longituderate controller D gain
|
|
// @Description: Loiter longitude rate controller D gain. Compensates for short-term change in desired speed vs actual speed
|
|
// @Range: 0.0 0.6
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
GGROUP(pid_loiter_rate_lon, "LOITER_LON_", AC_PID),
|
|
|
|
// @Param: THR_RATE_P
|
|
// @DisplayName: Throttle rate controller P gain
|
|
// @Description: Throttle rate controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
|
|
// @Range: 1.000 8.000
|
|
// @User: Standard
|
|
|
|
// @Param: THR_RATE_I
|
|
// @DisplayName: Throttle rate controller I gain
|
|
// @Description: Throttle rate controller I gain. Corrects long-term difference in desired vertical speed and actual speed
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: THR_RATE_IMAX
|
|
// @DisplayName: Throttle rate controller I gain maximum
|
|
// @Description: Throttle rate controller I gain maximum. Constrains the desired acceleration that the I gain will generate
|
|
// @Range: 0 500
|
|
// @Units: cm/s/s
|
|
// @User: Standard
|
|
|
|
// @Param: THR_RATE_D
|
|
// @DisplayName: Throttle rate controller D gain
|
|
// @Description: Throttle rate controller D gain. Compensates for short-term change in desired vertical speed vs actual speed
|
|
// @Range: 0.000 0.400
|
|
// @User: Standard
|
|
GGROUP(pid_throttle_rate, "THR_RATE_", AC_PID),
|
|
|
|
// @Param: THR_ACCEL_P
|
|
// @DisplayName: Throttle acceleration controller P gain
|
|
// @Description: Throttle acceleration controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output
|
|
// @Range: 0.500 1.500
|
|
// @User: Standard
|
|
|
|
// @Param: THR_ACCEL_I
|
|
// @DisplayName: Throttle acceleration controller I gain
|
|
// @Description: Throttle acceleration controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration
|
|
// @Range: 0.000 3.000
|
|
// @User: Standard
|
|
|
|
// @Param: THR_ACCEL_IMAX
|
|
// @DisplayName: Throttle acceleration controller I gain maximum
|
|
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
|
|
// @Range: 0 500
|
|
// @Units: ms
|
|
// @User: Standard
|
|
|
|
// @Param: THR_ACCEL_D
|
|
// @DisplayName: Throttle acceleration controller D gain
|
|
// @Description: Throttle acceleration controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration
|
|
// @Range: 0.000 0.400
|
|
// @User: Standard
|
|
GGROUP(pid_throttle_accel,"THR_ACCEL_", AC_PID),
|
|
|
|
// @Param: OF_RLL_P
|
|
// @DisplayName: Optical Flow based loiter controller roll axis P gain
|
|
// @Description: Optical Flow based loiter controller roll axis P gain. Converts the position error from the target point to a roll angle
|
|
// @Range: 2.000 3.000
|
|
// @User: Standard
|
|
|
|
// @Param: OF_RLL_I
|
|
// @DisplayName: Optical Flow based loiter controller roll axis I gain
|
|
// @Description: Optical Flow based loiter controller roll axis I gain. Corrects long-term position error by more persistently rolling left or right
|
|
// @Range: 0.250 0.750
|
|
// @User: Standard
|
|
|
|
// @Param: OF_RLL_IMAX
|
|
// @DisplayName: Optical Flow based loiter controller roll axis I gain maximum
|
|
// @Description: Optical Flow based loiter controller roll axis I gain maximum. Constrains the maximum roll angle that the I term will generate
|
|
// @Range: 0 4500
|
|
// @Units: Centi-Degrees
|
|
// @User: Standard
|
|
|
|
// @Param: OF_RLL_D
|
|
// @DisplayName: Optical Flow based loiter controller roll axis D gain
|
|
// @Description: Optical Flow based loiter controller roll axis D gain. Compensates for short-term change in speed in the roll direction
|
|
// @Range: 0.100 0.140
|
|
// @User: Standard
|
|
GGROUP(pid_optflow_roll, "OF_RLL_", AC_PID),
|
|
|
|
// @Param: OF_PIT_P
|
|
// @DisplayName: Optical Flow based loiter controller pitch axis P gain
|
|
// @Description: Optical Flow based loiter controller pitch axis P gain. Converts the position error from the target point to a pitch angle
|
|
// @Range: 2.000 3.000
|
|
// @User: Standard
|
|
|
|
// @Param: OF_PIT_I
|
|
// @DisplayName: Optical Flow based loiter controller pitch axis I gain
|
|
// @Description: Optical Flow based loiter controller pitch axis I gain. Corrects long-term position error by more persistently pitching left or right
|
|
// @Range: 0.250 0.750
|
|
// @User: Standard
|
|
|
|
// @Param: OF_PIT_IMAX
|
|
// @DisplayName: Optical Flow based loiter controller pitch axis I gain maximum
|
|
// @Description: Optical Flow based loiter controller pitch axis I gain maximum. Constrains the maximum pitch angle that the I term will generate
|
|
// @Range: 0 4500
|
|
// @Units: Centi-Degrees
|
|
// @User: Standard
|
|
|
|
// @Param: OF_PIT_D
|
|
// @DisplayName: Optical Flow based loiter controller pitch axis D gain
|
|
// @Description: Optical Flow based loiter controller pitch axis D gain. Compensates for short-term change in speed in the pitch direction
|
|
// @Range: 0.100 0.140
|
|
// @User: Standard
|
|
GGROUP(pid_optflow_pitch, "OF_PIT_", AC_PID),
|
|
|
|
// PI controller
|
|
//--------------
|
|
// @Param: STB_RLL_P
|
|
// @DisplayName: Roll axis stabilize controller P gain
|
|
// @Description: Roll axis stabilize (i.e. angle) controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
|
|
// @Range: 3.000 6.000
|
|
// @User: Standard
|
|
|
|
// @Param: STB_RLL_I
|
|
// @DisplayName: Roll axis stabilize controller I gain
|
|
// @Description: Roll axis stabilize (i.e. angle) controller I gain. Corrects for longer-term difference in desired roll angle and actual angle
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: STB_RLL_IMAX
|
|
// @DisplayName: Roll axis stabilize controller I gain maximum
|
|
// @Description: Roll axis stabilize (i.e. angle) controller I gain maximum. Constrains the maximum roll rate that the I term will generate
|
|
// @Range: 0 4500
|
|
// @Units: Centi-Degrees/Sec
|
|
// @User: Standard
|
|
GGROUP(pi_stabilize_roll, "STB_RLL_", APM_PI),
|
|
|
|
// @Param: STB_PIT_P
|
|
// @DisplayName: Pitch axis stabilize controller P gain
|
|
// @Description: Pitch axis stabilize (i.e. angle) controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
|
|
// @Range: 3.000 6.000
|
|
// @User: Standard
|
|
|
|
// @Param: STB_PIT_I
|
|
// @DisplayName: Pitch axis stabilize controller I gain
|
|
// @Description: Pitch axis stabilize (i.e. angle) controller I gain. Corrects for longer-term difference in desired pitch angle and actual angle
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: STB_PIT_IMAX
|
|
// @DisplayName: Pitch axis stabilize controller I gain maximum
|
|
// @Description: Pitch axis stabilize (i.e. angle) controller I gain maximum. Constrains the maximum pitch rate that the I term will generate
|
|
// @Range: 0 4500
|
|
// @Units: Centi-Degrees/Sec
|
|
// @User: Standard
|
|
GGROUP(pi_stabilize_pitch, "STB_PIT_", APM_PI),
|
|
|
|
// @Param: STB_YAW_P
|
|
// @DisplayName: Yaw axis stabilize controller P gain
|
|
// @Description: Yaw axis stabilize (i.e. angle) controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
|
|
// @Range: 3.000 6.000
|
|
// @User: Standard
|
|
|
|
// @Param: STB_YAW_I
|
|
// @DisplayName: Yaw axis stabilize controller I gain
|
|
// @Description: Yaw axis stabilize (i.e. angle) controller I gain. Corrects for longer-term difference in desired yaw angle and actual angle
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: STB_YAW_IMAX
|
|
// @DisplayName: Yaw axis stabilize controller I gain maximum
|
|
// @Description: Yaw axis stabilize (i.e. angle) controller I gain maximum. Constrains the maximum yaw rate that the I term will generate
|
|
// @Range: 0 4500
|
|
// @Units: Centi-Degrees/Sec
|
|
// @User: Standard
|
|
GGROUP(pi_stabilize_yaw, "STB_YAW_", APM_PI),
|
|
|
|
// @Param: THR_ALT_P
|
|
// @DisplayName: Altitude controller P gain
|
|
// @Description: Altitude controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller
|
|
// @Range: 1.000 3.000
|
|
// @User: Standard
|
|
|
|
// @Param: THR_ALT_I
|
|
// @DisplayName: Altitude controller I gain
|
|
// @Description: Altitude controller I gain. Corrects for longer-term difference in desired altitude and actual altitude
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: THR_ALT_IMAX
|
|
// @DisplayName: Altitude controller I gain maximum
|
|
// @Description: Altitude controller I gain maximum. Constrains the maximum climb rate rate that the I term will generate
|
|
// @Range: 0 500
|
|
// @Units: cm/s
|
|
// @User: Standard
|
|
GGROUP(pi_alt_hold, "THR_ALT_", APM_PI),
|
|
|
|
// @Param: HLD_LAT_P
|
|
// @DisplayName: Loiter latitude position controller P gain
|
|
// @Description: Loiter latitude position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller
|
|
// @Range: 0.100 0.300
|
|
// @User: Standard
|
|
|
|
// @Param: HLD_LAT_I
|
|
// @DisplayName: Loiter latitude position controller I gain
|
|
// @Description: Loiter latitude position controller I gain. Corrects for longer-term distance (in latitude) to the target location
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: HLD_LAT_IMAX
|
|
// @DisplayName: Loiter latitude position controller I gain maximum
|
|
// @Description: Loiter latitude position controller I gain maximum. Constrains the maximum desired speed that the I term will generate
|
|
// @Range: 0 3000
|
|
// @Units: cm/s
|
|
// @User: Standard
|
|
GGROUP(pi_loiter_lat, "HLD_LAT_", APM_PI),
|
|
|
|
// @Param: HLD_LON_P
|
|
// @DisplayName: Loiter longitude position controller P gain
|
|
// @Description: Loiter longitude position controller P gain. Converts the distance (in the longitude direction) to the target location into a desired speed which is then passed to the loiter longitude rate controller
|
|
// @Range: 0.100 0.300
|
|
// @User: Standard
|
|
|
|
// @Param: HLD_LON_I
|
|
// @DisplayName: Loiter longitude position controller I gain
|
|
// @Description: Loiter longitude position controller I gain. Corrects for longer-term distance (in longitude direction) to the target location
|
|
// @Range: 0.000 0.100
|
|
// @User: Standard
|
|
|
|
// @Param: HLD_LON_IMAX
|
|
// @DisplayName: Loiter longitudeposition controller I gain maximum
|
|
// @Description: Loiter longitudeposition controller I gain maximum. Constrains the maximum desired speed that the I term will generate
|
|
// @Range: 0 3000
|
|
// @Units: cm/s
|
|
// @User: Standard
|
|
GGROUP(pi_loiter_lon, "HLD_LON_", APM_PI),
|
|
|
|
// variables not in the g class which contain EEPROM saved variables
|
|
|
|
// variables not in the g class which contain EEPROM saved variables
|
|
#if CAMERA == ENABLED
|
|
// @Group: CAM_
|
|
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
|
GOBJECT(camera, "CAM_", AP_Camera),
|
|
#endif
|
|
|
|
// @Group: RELAY_
|
|
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
|
GOBJECT(relay, "RELAY_", AP_Relay),
|
|
|
|
// @Group: COMPASS_
|
|
// @Path: ../libraries/AP_Compass/Compass.cpp
|
|
GOBJECT(compass, "COMPASS_", Compass),
|
|
|
|
// @Group: INS_
|
|
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
GOBJECT(ins, "INS_", AP_InertialSensor),
|
|
#endif
|
|
|
|
// @Group: INAV_
|
|
// @Path: ../libraries/AP_InertialNav/AP_InertialNav.cpp
|
|
GOBJECT(inertial_nav, "INAV_", AP_InertialNav),
|
|
|
|
// @Group: WPNAV_
|
|
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
|
|
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
|
|
|
|
// @Group: SR0_
|
|
// @Path: GCS_Mavlink.pde
|
|
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
|
|
|
|
// @Group: SR3_
|
|
// @Path: GCS_Mavlink.pde
|
|
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
|
|
|
|
// @Group: AHRS_
|
|
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
|
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
|
|
|
#if MOUNT == ENABLED
|
|
// @Group: MNT_
|
|
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
|
GOBJECT(camera_mount, "MNT_", AP_Mount),
|
|
#endif
|
|
|
|
#if MOUNT2 == ENABLED
|
|
// @Group: MNT2_
|
|
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
|
|
GOBJECT(camera_mount2, "MNT2_", AP_Mount),
|
|
#endif
|
|
|
|
#if SPRAYER == ENABLED
|
|
// @Group: SPRAYER_
|
|
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
|
|
GOBJECT(sprayer, "SPRAY_", AC_Sprayer),
|
|
#endif
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
|
GOBJECT(sitl, "SIM_", SITL),
|
|
#endif
|
|
|
|
// @Group: GND_
|
|
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
|
|
GOBJECT(barometer, "GND_", AP_Baro),
|
|
|
|
// @Group: SCHED_
|
|
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
|
|
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
|
|
|
|
#if AC_FENCE == ENABLED
|
|
// @Group: FENCE_
|
|
// @Path: ../libraries/AC_Fence/AC_Fence.cpp
|
|
GOBJECT(fence, "FENCE_", AC_Fence),
|
|
#endif
|
|
|
|
// @Group: GPSGLITCH_
|
|
// @Path: ../libraries/AP_GPS/AP_GPS_Glitch.cpp
|
|
GOBJECT(gps_glitch, "GPSGLITCH_", GPS_Glitch),
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
// @Group: H_
|
|
// @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp
|
|
GOBJECT(motors, "H_", AP_MotorsHeli),
|
|
#else
|
|
// @Group: MOT_
|
|
// @Path: ../libraries/AP_Motors/AP_Motors_Class.cpp
|
|
GOBJECT(motors, "MOT_", AP_Motors),
|
|
#endif
|
|
|
|
// @Group: RCMAP_
|
|
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
|
|
GOBJECT(rcmap, "RCMAP_", RCMapper),
|
|
|
|
AP_VAREND
|
|
};
|
|
|
|
|
|
static void load_parameters(void)
|
|
{
|
|
// change the default for the AHRS_GPS_GAIN for ArduCopter
|
|
// if it hasn't been set by the user
|
|
if (!ahrs.gps_gain.load()) {
|
|
ahrs.gps_gain.set_and_save(1.0);
|
|
}
|
|
// disable centrifugal force correction, it will be enabled as part of the arming process
|
|
ahrs.set_correct_centrifugal(false);
|
|
|
|
// setup different AHRS gains for ArduCopter than the default
|
|
// but allow users to override in their config
|
|
if (!ahrs._kp.load()) {
|
|
ahrs._kp.set_and_save(0.1);
|
|
}
|
|
if (!ahrs._kp_yaw.load()) {
|
|
ahrs._kp_yaw.set_and_save(0.1);
|
|
}
|
|
|
|
// setup different Compass learn setting for ArduCopter than the default
|
|
// but allow users to override in their config
|
|
if (!compass._learn.load()) {
|
|
compass._learn.set_and_save(0);
|
|
}
|
|
|
|
if (!g.format_version.load() ||
|
|
g.format_version != Parameters::k_format_version) {
|
|
|
|
// erase all parameters
|
|
cliSerial->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
|
AP_Param::erase_all();
|
|
|
|
// save the current format version
|
|
g.format_version.set_and_save(Parameters::k_format_version);
|
|
cliSerial->println_P(PSTR("done."));
|
|
} else {
|
|
uint32_t before = micros();
|
|
// Load all auto-loaded EEPROM variables
|
|
AP_Param::load_all();
|
|
|
|
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
|
}
|
|
}
|