2015-05-29 23:12:49 -03:00
# include "Copter.h"
2013-08-29 02:34:47 -03:00
/*
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/>.
*/
2012-02-12 07:26:36 -04:00
/*
2012-08-21 23:19:50 -03:00
* ArduCopter parameter definitions
*
*/
2015-05-29 23:12:49 -03:00
# define GSCALAR(v, name, def) { copter.g.v.vtype, name, Parameters::k_param_ ## v, &copter.g.v, {def_value : def} }
# define ASCALAR(v, name, def) { copter.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&copter.aparm.v, {def_value : def} }
# define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &copter.g.v, {group_info : class::var_info} }
# define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info} }
2017-01-09 05:54:18 -04:00
# define GOBJECTPTR(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info}, AP_PARAM_FLAG_POINTER }
2017-03-14 06:47:18 -03:00
# define GOBJECTVARPTR(v, name, var_info_ptr) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info_ptr : var_info_ptr}, AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER }
2015-05-29 23:12:49 -03:00
# define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&copter.v, {group_info : class::var_info} }
2012-02-12 07:26:36 -04:00
2015-10-25 14:03:46 -03:00
const AP_Param : : Info Copter : : var_info [ ] = {
2012-12-10 08:45:57 -04:00
// @Param: SYSID_SW_MREV
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
2016-02-28 19:35:40 -04:00
// @ReadOnly: True
2012-08-21 23:19:50 -03:00
GSCALAR ( format_version , " SYSID_SW_MREV " , 0 ) ,
2012-12-10 08:45:57 -04:00
// @Param: SYSID_SW_TYPE
// @DisplayName: Software Type
// @Description: This is used by the ground station to recognise the software type (eg ArduPlane vs ArduCopter)
2017-08-22 22:24:42 -03:00
// @Values: 0:ArduPlane,4:AntennaTracker,10:Copter,20:Rover,40:ArduSub
2012-12-10 08:45:57 -04:00
// @User: Advanced
2016-02-28 19:35:40 -04:00
// @ReadOnly: True
2012-08-21 23:19:50 -03:00
GSCALAR ( software_type , " SYSID_SW_TYPE " , Parameters : : k_software_type ) ,
2012-02-12 07:26:36 -04:00
2012-12-10 08:45:57 -04:00
// @Param: SYSID_THISMAV
2015-05-10 21:21:13 -03:00
// @DisplayName: MAVLink system ID of this vehicle
// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
2014-01-13 21:11:00 -04:00
// @Range: 1 255
2012-12-10 08:45:57 -04:00
// @User: Advanced
2012-08-21 23:19:50 -03:00
GSCALAR ( sysid_this_mav , " SYSID_THISMAV " , MAV_SYSTEM_ID ) ,
2013-01-02 05:50:25 -04:00
// @Param: SYSID_MYGCS
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
2015-01-02 13:46:41 -04:00
// @Values: 255:Mission Planner and DroidPlanner, 252: AP Planner 2
2013-01-02 05:50:25 -04:00
// @User: Advanced
2012-08-21 23:19:50 -03:00
GSCALAR ( sysid_my_gcs , " SYSID_MYGCS " , 255 ) ,
2012-07-05 03:33:40 -03:00
2015-04-16 01:54:29 -03:00
// @Param: PILOT_THR_FILT
// @DisplayName: Throttle filter cutoff
// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
// @User: Advanced
// @Units: Hz
// @Range: 0 10
// @Increment: .5
GSCALAR ( throttle_filt , " PILOT_THR_FILT " , 0 ) ,
2015-04-30 03:06:55 -03:00
// @Param: PILOT_TKOFF_ALT
// @DisplayName: Pilot takeoff altitude
// @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.
// @User: Standard
2017-05-02 10:36:10 -03:00
// @Units: cm
2015-04-30 03:06:55 -03:00
// @Range: 0.0 1000.0
// @Increment: 10
2015-04-30 02:24:48 -03:00
GSCALAR ( pilot_takeoff_alt , " PILOT_TKOFF_ALT " , PILOT_TKOFF_ALT_DEFAULT ) ,
2015-04-30 03:06:55 -03:00
2015-04-30 03:04:17 -03:00
// @Param: PILOT_TKOFF_DZ
// @DisplayName: Takeoff trigger deadzone
// @Description: Offset from mid stick at which takeoff is triggered
// @User: Standard
2017-02-10 20:26:57 -04:00
// @Range: 0 500
2015-04-30 03:04:17 -03:00
// @Increment: 10
GSCALAR ( takeoff_trigger_dz , " PILOT_TKOFF_DZ " , THR_DZ_DEFAULT ) ,
// @Param: PILOT_THR_BHV
// @DisplayName: Throttle stick behavior
2016-01-06 17:39:36 -04:00
// @Description: Bitmask containing various throttle stick options. Add up the values for options that you want.
2015-04-30 03:04:17 -03:00
// @User: Standard
2016-01-11 19:59:42 -04:00
// @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
2015-04-30 03:04:17 -03:00
GSCALAR ( throttle_behavior , " PILOT_THR_BHV " , 0 ) ,
2015-01-19 09:52:54 -04:00
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
GOBJECT ( serial_manager , " SERIAL " , AP_SerialManager ) ,
2012-08-21 23:19:50 -03:00
2012-08-29 20:03:01 -03:00
// @Param: TELEM_DELAY
2012-10-21 18:32:39 -03:00
// @DisplayName: Telemetry startup delay
2012-08-29 20:03:01 -03:00
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
2013-11-26 09:17:02 -04:00
// @User: Advanced
2017-05-02 10:36:10 -03:00
// @Units: s
2016-08-29 03:29:05 -03:00
// @Range: 0 30
2012-08-29 20:03:01 -03:00
// @Increment: 1
GSCALAR ( telem_delay , " TELEM_DELAY " , 0 ) ,
2015-05-22 21:04:54 -03:00
// @Param: GCS_PID_MASK
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
// @Values: 0:None,1:Roll,2:Pitch,4:Yaw
2015-05-30 21:16:44 -03:00
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
2015-05-22 21:04:54 -03:00
GSCALAR ( gcs_pid_mask , " GCS_PID_MASK " , 0 ) ,
2013-01-02 05:50:25 -04:00
// @Param: RTL_ALT
2012-08-21 23:19:50 -03:00
// @DisplayName: RTL Altitude
2015-11-20 23:43:52 -04:00
// @Description: The minimum relative altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
2017-05-02 10:36:10 -03:00
// @Units: cm
2013-05-21 03:56:09 -03:00
// @Range: 0 8000
2012-08-21 23:19:50 -03:00
// @Increment: 1
// @User: Standard
2012-11-29 08:08:19 -04:00
GSCALAR ( rtl_altitude , " RTL_ALT " , RTL_ALT ) ,
2016-05-31 00:18:43 -03:00
2016-01-06 03:00:29 -04:00
// @Param: RTL_CONE_SLOPE
// @DisplayName: RTL cone slope
// @Description: Defines a cone above home which determines maximum climb
// @Range: 0.5 10.0
// @Increment: .1
2016-01-07 04:21:31 -04:00
// @Values: 0:Disabled,1:Shallow,3:Steep
2016-01-06 03:00:29 -04:00
// @User: Standard
2016-05-31 00:18:43 -03:00
GSCALAR ( rtl_cone_slope , " RTL_CONE_SLOPE " , RTL_CONE_SLOPE_DEFAULT ) ,
2012-08-21 23:19:50 -03:00
2015-10-19 21:19:37 -03:00
// @Param: RTL_SPEED
// @DisplayName: RTL speed
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.
// @Units: cm/s
// @Range: 0 2000
// @Increment: 50
// @User: Standard
GSCALAR ( rtl_speed_cms , " RTL_SPEED " , 0 ) ,
2014-07-16 16:15:31 -03:00
// @Param: RNGFND_GAIN
// @DisplayName: Rangefinder gain
2013-04-20 03:58:36 -03:00
// @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter
2013-11-24 23:52:37 -04:00
// @Range: 0.01 2.0
2013-04-20 03:58:36 -03:00
// @Increment: 0.01
// @User: Standard
2016-04-27 08:37:04 -03:00
GSCALAR ( rangefinder_gain , " RNGFND_GAIN " , RANGEFINDER_GAIN_DEFAULT ) ,
2013-04-20 03:58:36 -03:00
2012-12-10 10:47:14 -04:00
// @Param: FS_BATT_ENABLE
2012-11-13 10:43:54 -04:00
// @DisplayName: Battery Failsafe Enable
// @Description: Controls whether failsafe will be invoked when battery voltage or current runs low
2018-01-19 09:44:02 -04:00
// @Values: 0:Disabled,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land
2012-11-13 10:43:54 -04:00
// @User: Standard
2013-11-16 01:46:57 -04:00
GSCALAR ( failsafe_battery_enabled , " FS_BATT_ENABLE " , FS_BATT_DISABLED ) ,
2012-11-13 10:43:54 -04:00
2013-10-01 10:34:44 -03:00
// @Param: FS_BATT_VOLTAGE
// @DisplayName: Failsafe battery voltage
2013-10-09 19:31:31 -03:00
// @Description: Battery voltage to trigger failsafe. Set to 0 to disable battery voltage failsafe. If the battery voltage drops below this voltage then the copter will RTL
2017-05-02 10:36:10 -03:00
// @Units: V
2013-10-28 23:24:04 -03:00
// @Increment: 0.1
2013-10-01 10:34:44 -03:00
// @User: Standard
GSCALAR ( fs_batt_voltage , " FS_BATT_VOLTAGE " , FS_BATT_VOLTAGE_DEFAULT ) ,
// @Param: FS_BATT_MAH
// @DisplayName: Failsafe battery milliAmpHours
2013-10-09 19:31:31 -03:00
// @Description: Battery capacity remaining to trigger failsafe. Set to 0 to disable battery remaining failsafe. If the battery remaining drops below this level then the copter will RTL
2017-05-02 10:36:10 -03:00
// @Units: mA.h
2013-10-28 23:24:04 -03:00
// @Increment: 50
2013-10-01 10:34:44 -03:00
// @User: Standard
GSCALAR ( fs_batt_mah , " FS_BATT_MAH " , FS_BATT_MAH_DEFAULT ) ,
2013-04-29 09:30:22 -03:00
// @Param: FS_GCS_ENABLE
// @DisplayName: Ground Station Failsafe Enable
2014-11-13 17:10:06 -04:00
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. NB. The GCS Failsafe is only active when RC_OVERRIDE is being used to control the vehicle.
2018-01-19 09:44:02 -04:00
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always SmartRTL or RTL,4:Enabled always SmartRTL or Land
2013-04-29 09:30:22 -03:00
// @User: Standard
2014-04-08 22:50:35 -03:00
GSCALAR ( failsafe_gcs , " FS_GCS_ENABLE " , FS_GCS_ENABLED_ALWAYS_RTL ) ,
2013-04-29 09:30:22 -03:00
2013-08-15 01:04:43 -03:00
// @Param: GPS_HDOP_GOOD
// @DisplayName: GPS Hdop Good
2013-10-13 01:53:26 -03:00
// @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
2013-08-15 01:04:43 -03:00
// @Range: 100 900
// @User: Advanced
GSCALAR ( gps_hdop_good , " GPS_HDOP_GOOD " , GPS_HDOP_GOOD_DEFAULT ) ,
2012-08-21 23:19:50 -03:00
// @Param: MAG_ENABLE
2013-11-26 09:17:02 -04:00
// @DisplayName: Compass enable/disable
2012-08-21 23:19:50 -03:00
// @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: SUPER_SIMPLE
2013-11-26 09:35:11 -04:00
// @DisplayName: Super Simple Mode
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
2013-10-05 19:56:30 -03:00
// @Values: 0:Disabled,1:Mode1,2:Mode2,3:Mode1+2,4:Mode3,5:Mode1+3,6:Mode2+3,7:Mode1+2+3,8:Mode4,9:Mode1+4,10:Mode2+4,11:Mode1+2+4,12:Mode3+4,13:Mode1+3+4,14:Mode2+3+4,15:Mode1+2+3+4,16:Mode5,17:Mode1+5,18:Mode2+5,19:Mode1+2+5,20:Mode3+5,21:Mode1+3+5,22:Mode2+3+5,23:Mode1+2+3+5,24:Mode4+5,25:Mode1+4+5,26:Mode2+4+5,27:Mode1+2+4+5,28:Mode3+4+5,29:Mode1+3+4+5,30:Mode2+3+4+5,31:Mode1+2+3+4+5,32:Mode6,33:Mode1+6,34:Mode2+6,35:Mode1+2+6,36:Mode3+6,37:Mode1+3+6,38:Mode2+3+6,39:Mode1+2+3+6,40:Mode4+6,41:Mode1+4+6,42:Mode2+4+6,43:Mode1+2+4+6,44:Mode3+4+6,45:Mode1+3+4+6,46:Mode2+3+4+6,47:Mode1+2+3+4+6,48:Mode5+6,49:Mode1+5+6,50:Mode2+5+6,51:Mode1+2+5+6,52:Mode3+5+6,53:Mode1+3+5+6,54:Mode2+3+5+6,55:Mode1+2+3+5+6,56:Mode4+5+6,57:Mode1+4+5+6,58:Mode2+4+5+6,59:Mode1+2+4+5+6,60:Mode3+4+5+6,61:Mode1+3+4+5+6,62:Mode2+3+4+5+6,63:Mode1+2+3+4+5+6
2012-08-21 23:19:50 -03:00
// @User: Standard
2014-02-03 08:06:58 -04:00
GSCALAR ( super_simple , " SUPER_SIMPLE " , 0 ) ,
2012-08-21 23:19:50 -03:00
2012-11-29 08:08:19 -04:00
// @Param: RTL_ALT_FINAL
// @DisplayName: RTL Final Altitude
2013-01-14 02:20:33 -04:00
// @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.
2017-05-02 10:36:10 -03:00
// @Units: cm
2012-11-29 08:08:19 -04:00
// @Range: -1 1000
2012-08-21 23:19:50 -03:00
// @Increment: 1
// @User: Standard
2012-11-29 08:08:19 -04:00
GSCALAR ( rtl_alt_final , " RTL_ALT_FINAL " , RTL_ALT_FINAL ) ,
2012-08-21 23:19:50 -03:00
2015-07-12 22:39:54 -03:00
// @Param: RTL_CLIMB_MIN
// @DisplayName: RTL minimum climb
// @Description: The vehicle will climb this many cm during the initial climb portion of the RTL
2017-05-02 10:36:10 -03:00
// @Units: cm
2015-07-12 22:39:54 -03:00
// @Range: 0 3000
// @Increment: 10
// @User: Standard
GSCALAR ( rtl_climb_min , " RTL_CLIMB_MIN " , RTL_CLIMB_MIN_DEFAULT ) ,
2013-04-18 03:30:18 -03:00
// @Param: WP_YAW_BEHAVIOR
// @DisplayName: Yaw behaviour during missions
// @Description: Determines how the autopilot controls the yaw during missions and RTL
2013-07-20 03:46:19 -03:00
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course
2013-11-26 09:35:11 -04:00
// @User: Standard
2013-04-20 03:36:24 -03:00
GSCALAR ( wp_yaw_behavior , " WP_YAW_BEHAVIOR " , WP_YAW_BEHAVIOR_DEFAULT ) ,
2012-12-09 05:04:31 -04:00
2013-01-02 05:50:25 -04:00
// @Param: RTL_LOIT_TIME
2012-11-29 08:08:19 -04:00
// @DisplayName: RTL loiter time
2015-08-17 18:15:26 -03:00
// @Description: Time (in milliseconds) to loiter above home before beginning final descent
2012-11-29 08:08:19 -04:00
// @Units: ms
// @Range: 0 60000
// @Increment: 1000
// @User: Standard
GSCALAR ( rtl_loiter_time , " RTL_LOIT_TIME " , RTL_LOITER_TIME ) ,
2012-02-12 07:26:36 -04:00
2012-11-24 09:50:09 -04:00
// @Param: LAND_SPEED
// @DisplayName: Land speed
// @Description: The descent speed for the final stage of landing in cm/s
2013-06-23 03:52:46 -03:00
// @Units: cm/s
2013-11-19 03:46:16 -04:00
// @Range: 30 200
2012-11-24 09:50:09 -04:00
// @Increment: 10
// @User: Standard
GSCALAR ( land_speed , " LAND_SPEED " , LAND_SPEED ) ,
2016-03-29 22:03:41 -03:00
// @Param: LAND_SPEED_HIGH
// @DisplayName: Land speed high
// @Description: The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used
// @Units: cm/s
// @Range: 0 500
// @Increment: 10
// @User: Standard
GSCALAR ( land_speed_high , " LAND_SPEED_HIGH " , 0 ) ,
2017-11-08 09:25:53 -04:00
// @Param: PILOT_SPEED_UP
// @DisplayName: Pilot maximum vertical speed ascending
// @Description: The maximum vertical ascending velocity the pilot may request in cm/s
2017-05-02 10:36:10 -03:00
// @Units: cm/s
2014-04-30 00:05:02 -03:00
// @Range: 50 500
2012-12-21 23:52:49 -04:00
// @Increment: 10
// @User: Standard
2017-11-08 09:25:53 -04:00
GSCALAR ( pilot_speed_up , " PILOT_SPEED_UP " , PILOT_VELZ_MAX ) ,
2012-12-21 23:52:49 -04:00
2014-04-30 00:05:02 -03:00
// @Param: PILOT_ACCEL_Z
// @DisplayName: Pilot vertical acceleration
// @Description: The vertical acceleration used when pilot is controlling the altitude
// @Units: cm/s/s
// @Range: 50 500
// @Increment: 10
// @User: Standard
GSCALAR ( pilot_accel_z , " PILOT_ACCEL_Z " , PILOT_ACCEL_Z_DEFAULT ) ,
2012-12-10 10:38:43 -04:00
// @Param: FS_THR_ENABLE
2012-08-21 23:19:50 -03:00
// @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
2018-01-19 09:44:02 -04:00
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land
2012-08-21 23:19:50 -03:00
// @User: Standard
2017-04-24 05:07:27 -03:00
GSCALAR ( failsafe_throttle , " FS_THR_ENABLE " , FS_THR_ENABLED_ALWAYS_RTL ) ,
2012-07-05 03:33:40 -03:00
2012-12-10 10:38:43 -04:00
// @Param: FS_THR_VALUE
2012-08-21 23:19:50 -03:00
// @DisplayName: Throttle Failsafe Value
2017-05-15 20:16:12 -03:00
// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
2013-06-18 03:56:39 -03:00
// @Range: 925 1100
2017-05-02 10:36:10 -03:00
// @Units: PWM
2013-06-18 03:56:39 -03:00
// @Increment: 1
2012-08-21 23:19:50 -03:00
// @User: Standard
2012-12-10 10:38:43 -04:00
GSCALAR ( failsafe_throttle_value , " FS_THR_VALUE " , FS_THR_VALUE_DEFAULT ) ,
2012-07-05 03:33:40 -03:00
2013-10-27 10:13:42 -03:00
// @Param: THR_DZ
// @DisplayName: Throttle deadzone
2017-05-15 20:16:12 -03:00
// @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
2013-10-27 10:13:42 -03:00
// @User: Standard
// @Range: 0 300
2017-05-02 10:36:10 -03:00
// @Units: PWM
2013-10-27 10:13:42 -03:00
// @Increment: 1
GSCALAR ( throttle_deadzone , " THR_DZ " , THR_DZ_DEFAULT ) ,
2012-12-10 08:45:57 -04:00
// @Param: FLTMODE1
// @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230
2017-09-08 23:45:31 -03:00
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL
2012-12-10 08:45:57 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( flight_mode1 , " FLTMODE1 " , FLIGHT_MODE_1 ) ,
2012-12-10 08:45:57 -04:00
// @Param: FLTMODE2
// @DisplayName: Flight Mode 2
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
2017-09-08 23:45:31 -03:00
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL
2012-12-10 08:45:57 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( flight_mode2 , " FLTMODE2 " , FLIGHT_MODE_2 ) ,
2012-12-10 08:45:57 -04:00
// @Param: FLTMODE3
// @DisplayName: Flight Mode 3
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
2017-09-08 23:45:31 -03:00
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL
2012-12-10 08:45:57 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( flight_mode3 , " FLTMODE3 " , FLIGHT_MODE_3 ) ,
2012-12-10 08:45:57 -04:00
// @Param: FLTMODE4
// @DisplayName: Flight Mode 4
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
2017-09-08 23:45:31 -03:00
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL
2012-12-10 08:45:57 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( flight_mode4 , " FLTMODE4 " , FLIGHT_MODE_4 ) ,
2012-12-10 08:45:57 -04:00
// @Param: FLTMODE5
// @DisplayName: Flight Mode 5
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
2017-09-08 23:45:31 -03:00
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL
2012-12-10 08:45:57 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( flight_mode5 , " FLTMODE5 " , FLIGHT_MODE_5 ) ,
2012-12-10 08:45:57 -04:00
// @Param: FLTMODE6
// @DisplayName: Flight Mode 6
// @Description: Flight mode when Channel 5 pwm is >=1750
2017-09-08 23:45:31 -03:00
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL
2012-12-10 08:45:57 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( flight_mode6 , " FLTMODE6 " , FLIGHT_MODE_6 ) ,
2012-12-10 08:45:57 -04:00
2017-04-10 05:39:10 -03:00
// @Param: FLTMODE_CH
// @DisplayName: Flightmode channel
// @Description: RC Channel to use for flight mode control
// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8
// @User: Advanced
GSCALAR ( flight_mode_chan , " FLTMODE_CH " , CH_MODE_DEFAULT ) ,
2012-12-10 08:45:57 -04:00
// @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
2012-08-21 23:19:50 -03:00
GSCALAR ( simple_modes , " SIMPLE " , 0 ) ,
2012-02-12 07:26:36 -04:00
2012-07-05 03:33:40 -03:00
// @Param: LOG_BITMASK
2012-08-21 23:19:50 -03:00
// @DisplayName: Log bitmask
2014-10-16 21:37:49 -03:00
// @Description: 4 byte bitmap of log types to enable
2016-05-08 23:05:52 -03:00
// @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW
2013-11-26 09:35:11 -04:00
// @User: Standard
2012-08-21 23:19:50 -03:00
GSCALAR ( log_bitmask , " LOG_BITMASK " , DEFAULT_LOG_BITMASK ) ,
2012-12-10 08:45:57 -04:00
2015-07-12 21:27:00 -03:00
// @Param: ESC_CALIBRATION
2012-12-10 08:45:57 -04:00
// @DisplayName: ESC Calibration
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
// @User: Advanced
2016-08-30 23:53:53 -03:00
// @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 3:Start-up and automatically calibrate ESCs, 9:Disabled
2015-07-12 21:27:00 -03:00
GSCALAR ( esc_calibrate , " ESC_CALIBRATION " , 0 ) ,
2012-12-10 08:45:57 -04:00
// @Param: TUNE
// @DisplayName: Channel 6 Tuning
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
// @User: Standard
2017-10-04 23:21:23 -03:00
// @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,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,41:RangeFinder Gain,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,57:Winch
2012-08-21 23:19:50 -03:00
GSCALAR ( radio_tuning , " TUNE " , 0 ) ,
2012-12-10 08:45:57 -04:00
// @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
2012-08-21 23:19:50 -03:00
GSCALAR ( radio_tuning_low , " TUNE_LOW " , 0 ) ,
2012-12-10 08:45:57 -04:00
// @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
2012-08-21 23:19:50 -03:00
GSCALAR ( radio_tuning_high , " TUNE_HIGH " , 1000 ) ,
2012-12-10 08:45:57 -04:00
2016-12-14 21:26:36 -04:00
// @Param: FRAME_TYPE
// @DisplayName: Frame Type (+, X, V, etc)
2013-01-14 02:49:26 -04:00
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
2016-12-15 07:02:39 -04:00
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B
2012-12-10 08:45:57 -04:00
// @User: Standard
2017-05-12 10:35:23 -03:00
// @RebootRequired: True
2016-12-14 21:26:36 -04:00
GSCALAR ( frame_type , " FRAME_TYPE " , AP_Motors : : MOTOR_FRAME_TYPE_X ) ,
2012-12-06 04:40:36 -04:00
// @Param: CH7_OPT
// @DisplayName: Channel 7 option
2016-09-14 16:46:51 -03:00
// @Description: Select which function is performed when CH7 is above 1800 pwm
2017-10-04 23:21:23 -03:00
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
2014-07-11 22:26:15 -03:00
// @User: Standard
2015-03-17 09:10:21 -03:00
GSCALAR ( ch7_option , " CH7_OPT " , AUXSW_DO_NOTHING ) ,
2012-10-21 18:32:39 -03:00
2013-05-17 02:42:28 -03:00
// @Param: CH8_OPT
// @DisplayName: Channel 8 option
2016-09-14 16:46:51 -03:00
// @Description: Select which function is performed when CH8 is above 1800 pwm
2017-10-04 23:21:23 -03:00
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
2014-07-11 22:26:15 -03:00
// @User: Standard
2015-03-17 09:10:21 -03:00
GSCALAR ( ch8_option , " CH8_OPT " , AUXSW_DO_NOTHING ) ,
2013-05-17 02:42:28 -03:00
2015-03-10 15:21:31 -03:00
// @Param: CH9_OPT
// @DisplayName: Channel 9 option
2016-09-14 16:46:51 -03:00
// @Description: Select which function is performed when CH9 is above 1800 pwm
2017-10-04 23:21:23 -03:00
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
2015-03-10 15:21:31 -03:00
// @User: Standard
2015-03-17 09:10:21 -03:00
GSCALAR ( ch9_option , " CH9_OPT " , AUXSW_DO_NOTHING ) ,
2015-03-10 15:21:31 -03:00
// @Param: CH10_OPT
// @DisplayName: Channel 10 option
2016-09-14 16:46:51 -03:00
// @Description: Select which function is performed when CH10 is above 1800 pwm
2017-10-04 23:21:23 -03:00
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
2015-03-10 15:21:31 -03:00
// @User: Standard
2015-03-17 09:10:21 -03:00
GSCALAR ( ch10_option , " CH10_OPT " , AUXSW_DO_NOTHING ) ,
2015-03-10 15:21:31 -03:00
// @Param: CH11_OPT
// @DisplayName: Channel 11 option
2016-09-14 16:46:51 -03:00
// @Description: Select which function is performed when CH11 is above 1800 pwm
2017-10-04 23:21:23 -03:00
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
2015-03-10 15:21:31 -03:00
// @User: Standard
2015-03-17 09:10:21 -03:00
GSCALAR ( ch11_option , " CH11_OPT " , AUXSW_DO_NOTHING ) ,
2015-03-10 15:21:31 -03:00
// @Param: CH12_OPT
// @DisplayName: Channel 12 option
2016-09-14 16:46:51 -03:00
// @Description: Select which function is performed when CH12 is above 1800 pwm
2017-10-04 23:21:23 -03:00
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
2015-03-10 15:21:31 -03:00
// @User: Standard
2015-03-17 09:10:21 -03:00
GSCALAR ( ch12_option , " CH12_OPT " , AUXSW_DO_NOTHING ) ,
2015-03-10 15:21:31 -03:00
2017-01-09 03:45:48 -04:00
// @Group: ARMING_
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
GOBJECT ( arming , " ARMING_ " , AP_Arming_Copter ) ,
2013-05-20 02:48:04 -03:00
2015-08-30 22:44:08 -03:00
// @Param: DISARM_DELAY
// @DisplayName: Disarm delay
// @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.
2017-05-02 10:36:10 -03:00
// @Units: s
2015-08-30 22:44:08 -03:00
// @Range: 0 127
// @User: Advanced
GSCALAR ( disarm_delay , " DISARM_DELAY " , AUTO_DISARMING_DELAY ) ,
2013-08-11 00:51:08 -03:00
// @Param: ANGLE_MAX
// @DisplayName: Angle Max
// @Description: Maximum lean angle in all flight modes
2017-05-02 10:36:10 -03:00
// @Units: cdeg
2015-08-13 14:35:32 -03:00
// @Range: 1000 8000
2013-08-11 00:51:08 -03:00
// @User: Advanced
2013-10-18 05:03:31 -03:00
ASCALAR ( angle_max , " ANGLE_MAX " , DEFAULT_ANGLE_MAX ) ,
2013-08-11 00:51:08 -03:00
2014-02-12 03:28:41 -04:00
// @Param: RC_FEEL_RP
// @DisplayName: RC Feel Roll/Pitch
2014-04-29 03:56:49 -03:00
// @Description: RC feel for roll/pitch which controls vehicle response to user input with 0 being extremely soft and 100 being crisp
2014-04-28 21:44:09 -03:00
// @Range: 0 100
2016-03-07 20:23:10 -04:00
// @Increment: 10
2014-04-28 21:44:09 -03:00
// @User: Standard
2014-02-12 03:28:41 -04:00
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
2017-07-02 21:33:36 -03:00
GSCALAR ( rc_feel_rp , " RC_FEEL_RP " , RC_FEEL_RP_MEDIUM ) ,
2014-02-12 03:28:41 -04:00
2014-07-11 02:08:09 -03:00
// @Param: PHLD_BRAKE_RATE
// @DisplayName: PosHold braking rate
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
2017-05-02 10:36:10 -03:00
// @Units: deg/s
2014-04-23 00:35:45 -03:00
// @Range: 4 12
2014-04-11 05:15:09 -03:00
// @User: Advanced
2014-07-11 02:08:09 -03:00
GSCALAR ( poshold_brake_rate , " PHLD_BRAKE_RATE " , POSHOLD_BRAKE_RATE_DEFAULT ) ,
2014-04-11 05:15:09 -03:00
2014-07-11 02:08:09 -03:00
// @Param: PHLD_BRAKE_ANGLE
// @DisplayName: PosHold braking angle max
// @Description: PosHold flight mode's max lean angle during braking in centi-degrees
2017-05-02 10:36:10 -03:00
// @Units: cdeg
2014-04-23 00:35:45 -03:00
// @Range: 2000 4500
2014-04-11 05:15:09 -03:00
// @User: Advanced
2014-07-11 02:08:09 -03:00
GSCALAR ( poshold_brake_angle_max , " PHLD_BRAKE_ANGLE " , POSHOLD_BRAKE_ANGLE_DEFAULT ) ,
2014-04-11 05:15:09 -03:00
2014-07-06 06:05:43 -03:00
// @Param: LAND_REPOSITION
// @DisplayName: Land repositioning
// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
2014-09-09 16:34:59 -03:00
// @Values: 0:No repositioning, 1:Repositioning
2014-07-06 06:05:43 -03:00
// @User: Advanced
GSCALAR ( land_repositioning , " LAND_REPOSITION " , LAND_REPOSITION_DEFAULT ) ,
2015-06-09 23:39:06 -03:00
// @Param: FS_EKF_ACTION
// @DisplayName: EKF Failsafe Action
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
// @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize
// @User: Advanced
GSCALAR ( fs_ekf_action , " FS_EKF_ACTION " , FS_EKF_ACTION_DEFAULT ) ,
2015-06-09 22:16:52 -03:00
// @Param: FS_EKF_THRESH
// @DisplayName: EKF failsafe variance threshold
// @Description: Allows setting the maximum acceptable compass and velocity variance
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
2014-07-21 07:07:15 -03:00
// @User: Advanced
2015-06-09 22:16:52 -03:00
GSCALAR ( fs_ekf_thresh , " FS_EKF_THRESH " , FS_EKF_THRESHOLD_DEFAULT ) ,
2014-07-21 07:07:15 -03:00
2015-08-30 23:15:46 -03:00
// @Param: FS_CRASH_CHECK
// @DisplayName: Crash check enable
// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
GSCALAR ( fs_crash_check , " FS_CRASH_CHECK " , 1 ) ,
2013-11-09 01:25:06 -04:00
2012-08-21 23:19:50 -03:00
// @Param: RC_SPEED
// @DisplayName: ESC Update Speed
// @Description: This is the speed in Hertz that your ESCs will receive updates
2013-05-21 04:31:16 -03:00
// @Units: Hz
// @Range: 50 490
// @Increment: 1
2012-08-21 23:19:50 -03:00
// @User: Advanced
GSCALAR ( rc_speed , " RC_SPEED " , RC_FAST_SPEED ) ,
2013-08-04 08:22:12 -03:00
// @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.
2012-12-10 08:45:57 -04:00
// @Range: 1 10
// @User: Standard
2013-08-04 08:22:12 -03:00
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 ) ,
2012-12-10 08:45:57 -04:00
2012-10-23 09:30:50 -03:00
// @Param: ACRO_BAL_ROLL
// @DisplayName: Acro Balance Roll
2014-10-14 00:42:14 -03:00
// @Description: rate at which roll angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
2013-08-04 06:14:07 -03:00
// @Range: 0 3
// @Increment: 0.1
2012-10-23 09:30:50 -03:00
// @User: Advanced
GSCALAR ( acro_balance_roll , " ACRO_BAL_ROLL " , ACRO_BALANCE_ROLL ) ,
// @Param: ACRO_BAL_PITCH
// @DisplayName: Acro Balance Pitch
2014-10-14 00:42:14 -03:00
// @Description: rate at which pitch angle returns to level in acro mode. A higher value causes the vehicle to return to level faster.
2013-08-04 06:14:07 -03:00
// @Range: 0 3
// @Increment: 0.1
2012-10-23 09:30:50 -03:00
// @User: Advanced
GSCALAR ( acro_balance_pitch , " ACRO_BAL_PITCH " , ACRO_BALANCE_PITCH ) ,
2012-12-10 09:27:46 -04:00
// @Param: ACRO_TRAINER
2013-08-04 06:14:07 -03:00
// @DisplayName: Acro Trainer
// @Description: Type of trainer used in acro mode
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
2012-12-10 09:27:46 -04:00
// @User: Advanced
2013-08-04 06:14:07 -03:00
GSCALAR ( acro_trainer , " ACRO_TRAINER " , ACRO_TRAINER_LIMITED ) ,
2012-12-10 09:27:46 -04:00
2016-06-22 01:16:28 -03:00
// @Param: ACRO_RP_EXPO
// @DisplayName: Acro Roll/Pitch Expo
2014-08-12 23:25:59 -03:00
// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
2014-08-19 00:51:27 -03:00
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
2016-06-22 01:16:28 -03:00
// @Range: -0.5 1.0
2014-08-12 23:25:59 -03:00
// @User: Advanced
2016-06-22 01:16:28 -03:00
GSCALAR ( acro_rp_expo , " ACRO_RP_EXPO " , ACRO_RP_EXPO_DEFAULT ) ,
2014-08-12 23:25:59 -03:00
2012-08-21 23:19:50 -03:00
// variables not in the g class which contain EEPROM saved variables
2012-12-22 04:26:27 -04:00
# if CAMERA == ENABLED
// @Group: CAM_
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
GOBJECT ( camera , " CAM_ " , AP_Camera ) ,
# endif
2013-06-24 23:46:53 -03:00
// @Group: RELAY_
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT ( relay , " RELAY_ " , AP_Relay ) ,
2014-04-02 12:19:54 -03:00
# if PARACHUTE == ENABLED
// @Group: CHUTE_
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
GOBJECT ( parachute , " CHUTE_ " , AP_Parachute ) ,
# endif
2015-01-06 00:24:50 -04:00
// @Group: LGR_
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
2015-01-06 22:53:21 -04:00
GOBJECT ( landinggear , " LGR_ " , AP_LandingGear ) ,
2015-01-06 00:24:50 -04:00
2015-10-12 11:27:26 -03:00
# if FRAME_CONFIG == HELI_FRAME
// @Group: IM_
2015-11-12 22:49:25 -04:00
// @Path: ../libraries/AC_InputManager/AC_InputManager_Heli.cpp
2015-10-12 11:27:26 -03:00
GOBJECT ( input_manager , " IM_ " , AC_InputManager_Heli ) ,
# endif
2012-08-21 23:19:50 -03:00
// @Group: COMPASS_
2016-03-15 11:16:23 -03:00
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
2012-08-21 23:19:50 -03:00
GOBJECT ( compass , " COMPASS_ " , Compass ) ,
// @Group: INS_
2012-11-05 00:32:38 -04:00
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
GOBJECT ( ins , " INS_ " , AP_InertialSensor ) ,
2012-07-19 02:56:13 -03:00
2013-07-18 01:58:24 -03:00
// @Group: WPNAV_
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
2017-01-09 05:54:18 -04:00
GOBJECTPTR ( wp_nav , " WPNAV_ " , AC_WPNav ) ,
2013-04-05 06:32:36 -03:00
2018-02-23 05:51:17 -04:00
# if MODE_CIRCLE_ENABLED == ENABLED
2014-04-24 20:53:03 -03:00
// @Group: CIRCLE_
2014-01-27 01:09:29 -04:00
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
2017-01-09 05:54:18 -04:00
GOBJECTPTR ( circle_nav , " CIRCLE_ " , AC_Circle ) ,
2018-02-23 05:51:17 -04:00
# endif
2014-01-27 01:09:29 -04:00
2014-04-24 20:53:03 -03:00
// @Group: ATC_
2017-02-06 00:34:18 -04:00
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
2017-01-09 06:10:32 -04:00
# if FRAME_CONFIG == HELI_FRAME
GOBJECTPTR ( attitude_control , " ATC_ " , AC_AttitudeControl_Heli ) ,
# else
2017-01-09 05:54:18 -04:00
GOBJECTPTR ( attitude_control , " ATC_ " , AC_AttitudeControl_Multi ) ,
2017-01-09 06:10:32 -04:00
# endif
2017-03-01 01:58:00 -04:00
// @Group: PSC
2014-01-10 10:29:55 -04:00
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
2017-01-09 05:54:18 -04:00
GOBJECTPTR ( pos_control , " PSC " , AC_PosControl ) ,
2014-01-10 10:29:55 -04:00
2013-01-02 10:36:48 -04:00
// @Group: SR0_
2015-06-15 20:59:39 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 22:14:55 -04:00
GOBJECTN ( _gcs . _chan [ 0 ] , gcs0 , " SR0_ " , GCS_MAVLINK ) ,
2013-01-02 10:36:48 -04:00
2013-11-23 06:45:42 -04:00
// @Group: SR1_
2015-06-15 20:59:39 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 22:14:55 -04:00
GOBJECTN ( _gcs . _chan [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK ) ,
2013-11-23 06:45:42 -04:00
// @Group: SR2_
2015-06-15 20:59:39 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 22:14:55 -04:00
GOBJECTN ( _gcs . _chan [ 2 ] , gcs2 , " SR2_ " , GCS_MAVLINK ) ,
2012-04-25 13:23:46 -03:00
2015-05-15 01:24:18 -03:00
// @Group: SR3_
2015-06-15 20:59:39 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 22:14:55 -04:00
GOBJECTN ( _gcs . _chan [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK ) ,
2015-05-15 01:24:18 -03:00
2012-08-21 23:19:50 -03:00
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT ( ahrs , " AHRS_ " , AP_AHRS ) ,
2012-04-04 10:55:07 -03:00
2012-07-15 04:36:05 -03:00
# if MOUNT == ENABLED
2015-04-28 21:07:36 -03:00
// @Group: MNT
2012-08-21 23:19:50 -03:00
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
2015-01-12 08:12:15 -04:00
GOBJECT ( camera_mount , " MNT " , AP_Mount ) ,
2012-07-15 04:36:05 -03:00
# endif
2015-11-09 18:14:31 -04:00
// @Group: LOG
// @Path: ../libraries/DataFlash/DataFlash.cpp
GOBJECT ( DataFlash , " LOG " , DataFlash_Class ) ,
2015-08-25 23:14:58 -03:00
// @Group: BATT
2013-10-01 10:34:44 -03:00
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
2014-12-01 00:29:39 -04:00
GOBJECT ( battery , " BATT " , AP_BattMonitor ) ,
2013-10-01 10:34:44 -03:00
2014-01-19 21:58:12 -04:00
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
2014-08-18 02:25:37 -03:00
GOBJECT ( BoardConfig , " BRD_ " , AP_BoardConfig ) ,
2014-01-19 21:58:12 -04:00
2017-05-06 06:11:50 -03:00
# if HAL_WITH_UAVCAN
// @Group: CAN_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp
GOBJECT ( BoardConfig_CAN , " CAN_ " , AP_BoardConfig_CAN ) ,
# endif
2013-08-04 11:20:21 -03:00
# if SPRAYER == ENABLED
2014-04-24 20:53:03 -03:00
// @Group: SPRAY_
2013-08-04 11:20:21 -03:00
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
GOBJECT ( sprayer , " SPRAY_ " , AC_Sprayer ) ,
# endif
2015-05-04 03:18:46 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2015-10-22 10:04:42 -03:00
GOBJECT ( sitl , " SIM_ " , SITL : : SITL ) ,
2012-08-21 23:19:50 -03:00
# endif
2013-05-21 02:22:11 -03:00
// @Group: GND_
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
2012-12-18 06:15:11 -04:00
GOBJECT ( barometer , " GND_ " , AP_Baro ) ,
2013-05-21 02:22:11 -03:00
2014-03-31 16:18:16 -03:00
// GPS driver
// @Group: GPS_
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
GOBJECT ( gps , " GPS_ " , AP_GPS ) ,
2013-05-21 02:22:11 -03:00
// @Group: SCHED_
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
2013-01-11 21:01:10 -04:00
GOBJECT ( scheduler , " SCHED_ " , AP_Scheduler ) ,
2012-12-18 06:15:11 -04:00
2013-04-26 06:51:07 -03:00
# if AC_FENCE == ENABLED
2013-07-18 01:58:24 -03:00
// @Group: FENCE_
// @Path: ../libraries/AC_Fence/AC_Fence.cpp
2013-04-26 06:51:07 -03:00
GOBJECT ( fence , " FENCE_ " , AC_Fence ) ,
2012-12-13 03:07:34 -04:00
# endif
2012-08-21 23:19:50 -03:00
2016-06-20 05:27:14 -03:00
// @Group: AVOID_
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
2017-01-02 20:36:26 -04:00
# if AC_AVOID_ENABLED == ENABLED
2016-06-20 05:27:14 -03:00
GOBJECT ( avoid , " AVOID_ " , AC_Avoid ) ,
2017-01-02 20:36:26 -04:00
# endif
2016-06-20 05:27:14 -03:00
2014-04-06 22:18:43 -03:00
# if AC_RALLY == ENABLED
// @Group: RALLY_
2016-07-19 19:52:56 -03:00
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
GOBJECT ( rally , " RALLY_ " , AP_Rally_Copter ) ,
2014-04-06 22:18:43 -03:00
# endif
2016-12-12 08:36:38 -04:00
# if FRAME_CONFIG == HELI_FRAME
2012-08-21 23:19:50 -03:00
// @Group: H_
2017-03-14 06:47:18 -03:00
// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli_Dual.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp
GOBJECTVARPTR ( motors , " H_ " , & copter . motors_var_info ) ,
2012-08-21 23:19:50 -03:00
# else
2013-01-02 04:05:57 -04:00
// @Group: MOT_
2015-08-25 23:14:58 -03:00
// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
2017-03-14 06:47:18 -03:00
GOBJECTVARPTR ( motors , " MOT_ " , & copter . motors_var_info ) ,
2012-06-29 02:10:35 -03:00
# endif
2013-03-24 23:48:06 -03:00
// @Group: RCMAP_
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
GOBJECT ( rcmap , " RCMAP_ " , RCMapper ) ,
2015-09-21 02:28:04 -03:00
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN ( EKF2 , NavEKF2 , " EK2_ " , NavEKF2 ) ,
2016-07-14 02:08:43 -03:00
// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN ( EKF3 , NavEKF3 , " EK3_ " , NavEKF3 ) ,
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2014-02-27 21:15:40 -04:00
// @Group: MIS_
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
GOBJECT ( mission , " MIS_ " , AP_Mission ) ,
2018-02-21 22:06:07 -04:00
# endif
2014-02-27 21:15:40 -04:00
2015-08-28 03:00:55 -03:00
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
2017-05-25 05:53:20 -03:00
GOBJECT ( rssi , " RSSI_ " , AP_RSSI ) ,
2015-08-28 03:00:55 -03:00
2016-04-27 07:55:35 -03:00
# if RANGEFINDER_ENABLED == ENABLED
2014-07-16 16:15:31 -03:00
// @Group: RNGFND
2014-06-27 01:23:56 -03:00
// @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
2016-04-27 08:37:04 -03:00
GOBJECT ( rangefinder , " RNGFND " , RangeFinder ) ,
2014-06-27 01:23:56 -03:00
# endif
2015-11-13 23:38:47 -04:00
# if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2014-07-25 00:12:10 -03:00
// @Group: TERRAIN_
2014-07-22 05:22:36 -03:00
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
GOBJECT ( terrain , " TERRAIN_ " , AP_Terrain ) ,
# endif
2014-07-11 23:32:00 -03:00
# if OPTFLOW == ENABLED
// @Group: FLOW
2014-10-17 01:54:53 -03:00
// @Path: ../libraries/AP_OpticalFlow/OpticalFlow.cpp
2014-07-11 23:32:00 -03:00
GOBJECT ( optflow , " FLOW " , OpticalFlow ) ,
# endif
2015-02-16 00:39:18 -04:00
# if PRECISION_LANDING == ENABLED
2016-01-06 23:55:44 -04:00
// @Group: PLND_
2015-02-16 00:39:18 -04:00
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
2015-12-31 02:27:52 -04:00
GOBJECT ( precland , " PLND_ " , AC_PrecLand ) ,
2015-02-16 00:39:18 -04:00
# endif
2015-08-07 02:34:56 -03:00
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT ( rpm_sensor , " RPM " , AP_RPM ) ,
2018-02-16 10:21:55 -04:00
# if ADSB_ENABLED == ENABLED
2015-11-25 19:22:21 -04:00
// @Group: ADSB_
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
GOBJECT ( adsb , " ADSB_ " , AP_ADSB ) ,
2016-07-21 09:44:09 -03:00
// @Group: AVD_
// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
GOBJECT ( avoidance_adsb , " AVD_ " , AP_Avoidance_Copter ) ,
2018-02-16 10:21:55 -04:00
# endif
2016-07-21 09:44:09 -03:00
2015-08-23 02:55:02 -03:00
// @Param: AUTOTUNE_AXES
2015-02-11 08:17:58 -04:00
// @DisplayName: Autotune axis bitmask
// @Description: 1-byte bitmap of axes to autotune
2015-03-11 02:33:37 -03:00
// @Values: 7:All,1:Roll Only,2:Pitch Only,4:Yaw Only,3:Roll and Pitch,5:Roll and Yaw,6:Pitch and Yaw
2015-05-30 21:16:44 -03:00
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
2015-02-11 08:17:58 -04:00
// @User: Standard
GSCALAR ( autotune_axis_bitmask , " AUTOTUNE_AXES " , 7 ) , // AUTOTUNE_AXIS_BITMASK_DEFAULT
2015-08-23 02:55:02 -03:00
// @Param: AUTOTUNE_AGGR
// @DisplayName: Autotune aggressiveness
// @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
2015-03-04 01:27:10 -04:00
// @Range: 0.05 0.10
// @User: Standard
2015-04-14 09:58:57 -03:00
GSCALAR ( autotune_aggressiveness , " AUTOTUNE_AGGR " , 0.1f ) ,
2015-03-04 01:27:10 -04:00
2015-08-23 02:44:45 -03:00
// @Param: AUTOTUNE_MIN_D
// @DisplayName: AutoTune minimum D
// @Description: Defines the minimum D gain
// @Range: 0.001 0.006
// @User: Standard
2015-11-29 22:21:40 -04:00
GSCALAR ( autotune_min_d , " AUTOTUNE_MIN_D " , 0.001f ) ,
2015-08-23 02:44:45 -03:00
2015-12-03 16:48:03 -04:00
// @Group: NTF_
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT ( notify , " NTF_ " , AP_Notify ) ,
2015-12-18 05:46:56 -04:00
// @Param: THROW_MOT_START
// @DisplayName: Start motors before throwing is detected
// @Description: Used by THROW mode. Controls whether motors will run at the speed set by THR_MIN or will be stopped when armed and waiting for the throw.
// @Values: 0:Stopped,1:Running
// @User: Standard
GSCALAR ( throw_motor_start , " THROW_MOT_START " , 0 ) ,
2016-04-21 02:04:19 -03:00
// @Param: TERRAIN_FOLLOW
// @DisplayName: Terrain Following use control
// @Description: This enables terrain following for RTL and LAND flight modes. To use this option TERRAIN_ENABLE must be 1 and the GCS must support sending terrain data to the aircraft. In RTL the RTL_ALT will be considered a height above the terrain. In LAND mode the vehicle will slow to LAND_SPEED 10m above terrain (instead of 10m above home). This parameter does not affect AUTO and Guided which use a per-command flag to determine if the height is above-home, absolute or above-terrain.
2016-06-08 02:14:24 -03:00
// @Values: 0:Do Not Use in RTL and Land,1:Use in RTL and Land
2016-03-19 03:25:13 -03:00
// @User: Standard
2016-04-21 02:04:19 -03:00
GSCALAR ( terrain_follow , " TERRAIN_FOLLOW " , 0 ) ,
2016-03-19 03:25:13 -03:00
2017-05-25 05:53:20 -03:00
// @Group:
2016-06-04 23:37:55 -03:00
// @Path: Parameters.cpp
GOBJECT ( g2 , " " , ParametersG2 ) ,
2017-08-19 00:37:19 -03:00
2012-08-21 23:19:50 -03:00
AP_VAREND
2012-02-12 07:26:36 -04:00
} ;
2016-06-04 23:37:55 -03:00
/*
2 nd group of parameters
*/
const AP_Param : : GroupInfo ParametersG2 : : var_info [ ] = {
2016-08-15 00:57:38 -03:00
// @Param: WP_NAVALT_MIN
// @DisplayName: Minimum navigation altitude
// @Description: This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing.
2016-06-04 23:37:55 -03:00
// @Range: 0 5
// @User: Standard
2016-08-15 00:57:38 -03:00
AP_GROUPINFO ( " WP_NAVALT_MIN " , 1 , ParametersG2 , wp_navalt_min , 0 ) ,
2016-06-04 23:37:55 -03:00
2016-07-21 22:24:13 -03:00
// @Group: BTN_
// @Path: ../libraries/AP_Button/AP_Button.cpp
AP_SUBGROUPINFO ( button , " BTN_ " , 2 , ParametersG2 , AP_Button ) ,
2016-08-01 09:42:09 -03:00
// @Param: THROW_NEXTMODE
// @DisplayName: Throw mode's follow up mode
// @Description: Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)
2017-08-25 22:47:14 -03:00
// @Values: 3:Auto,4:Guided,5:LOITER,6:RTL,9:Land,17:Brake,18:Throw
2016-08-01 09:42:09 -03:00
// @User: Standard
AP_GROUPINFO ( " THROW_NEXTMODE " , 3 , ParametersG2 , throw_nextmode , 18 ) ,
2016-08-01 23:26:48 -03:00
// @Param: THROW_TYPE
// @DisplayName: Type of Type
// @Description: Used by THROW mode. Specifies whether Copter is thrown upward or dropped.
// @Values: 0:Upward Throw,1:Drop
// @User: Standard
AP_GROUPINFO ( " THROW_TYPE " , 4 , ParametersG2 , throw_type , ThrowType_Upward ) ,
2016-08-08 05:16:36 -03:00
// @Param: GND_EFFECT_COMP
// @DisplayName: Ground Effect Compensation Enable/Disable
// @Description: Ground Effect Compensation Enable/Disable
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO ( " GND_EFFECT_COMP " , 5 , ParametersG2 , gndeffect_comp_enabled , 0 ) ,
2016-08-16 07:23:27 -03:00
# if ADVANCED_FAILSAFE == ENABLED
// @Group: AFS_
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
AP_SUBGROUPINFO ( afs , " AFS_ " , 6 , ParametersG2 , AP_AdvancedFailsafe ) ,
# endif
2016-09-12 03:23:53 -03:00
// @Param: DEV_OPTIONS
// @DisplayName: Development options
// @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning
// @Bitmask: 0:ADSBMavlinkProcessing
// @User: Advanced
AP_GROUPINFO ( " DEV_OPTIONS " , 7 , ParametersG2 , dev_options , 0 ) ,
2016-10-14 02:02:29 -03:00
2018-02-27 08:48:59 -04:00
# if BEACON_ENABLED == ENABLED
2017-01-02 20:36:26 -04:00
// @Group: BCN
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
AP_SUBGROUPINFO ( beacon , " BCN " , 14 , ParametersG2 , AP_Beacon ) ,
2018-02-22 00:53:20 -04:00
# endif
2017-01-02 20:36:26 -04:00
2016-10-14 02:02:29 -03:00
# if PROXIMITY_ENABLED == ENABLED
2016-10-19 05:24:20 -03:00
// @Group: PRX
2016-10-14 02:02:29 -03:00
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
2016-10-19 05:24:20 -03:00
AP_SUBGROUPINFO ( proximity , " PRX " , 8 , ParametersG2 , AP_Proximity ) ,
2016-10-14 02:02:29 -03:00
# endif
2016-06-22 01:16:28 -03:00
// @Param: ACRO_Y_EXPO
// @DisplayName: Acro Yaw Expo
// @Description: Acro yaw expo to allow faster rotation when stick at edges
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
// @Range: -0.5 1.0
// @User: Advanced
AP_GROUPINFO ( " ACRO_Y_EXPO " , 9 , ParametersG2 , acro_y_expo , ACRO_Y_EXPO_DEFAULT ) ,
// @Param: ACRO_THR_MID
// @DisplayName: Acro Thr Mid
// @Description: Acro Throttle Mid
// @Range: 0 1
// @User: Advanced
AP_GROUPINFO ( " ACRO_THR_MID " , 10 , ParametersG2 , acro_thr_mid , ACRO_THR_MID_DEFAULT ) ,
2017-02-28 02:06:51 -04:00
// @Param: SYSID_ENFORCE
2016-08-19 01:36:47 -03:00
// @DisplayName: GCS sysid enforcement
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
// @Values: 0:NotEnforced,1:Enforced
// @User: Advanced
AP_GROUPINFO ( " SYSID_ENFORCE " , 11 , ParametersG2 , sysid_enforce , 0 ) ,
2018-02-28 08:20:57 -04:00
# if STATS_ENABLED == ENABLED
2016-10-13 03:30:30 -03:00
// @Group: STAT
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
AP_SUBGROUPINFO ( stats , " STAT " , 12 , ParametersG2 , AP_Stats ) ,
2018-02-28 08:20:57 -04:00
# endif
2016-10-28 19:08:22 -03:00
# if GRIPPER_ENABLED == ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO ( gripper , " GRIP_ " , 13 , ParametersG2 , AP_Gripper ) ,
# endif
2016-12-12 06:22:56 -04:00
// @Param: FRAME_CLASS
// @DisplayName: Frame Class
// @Description: Controls major frame class for multicopter component
2017-05-13 22:15:02 -03:00
// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 11:Heli_Dual, 12:DodecaHexa
2016-12-12 06:22:56 -04:00
// @User: Standard
2017-05-12 10:35:23 -03:00
// @RebootRequired: True
2016-12-12 06:22:56 -04:00
AP_GROUPINFO ( " FRAME_CLASS " , 15 , ParametersG2 , frame_class , 0 ) ,
2017-01-06 21:06:40 -04:00
// @Group: SERVO
2017-02-05 22:16:08 -04:00
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
2017-01-06 21:06:40 -04:00
AP_SUBGROUPINFO ( servo_channels , " SERVO " , 16 , ParametersG2 , SRV_Channels ) ,
// @Group: RC
2017-02-05 22:16:08 -04:00
// @Path: ../libraries/RC_Channel/RC_Channels.cpp
2017-01-06 21:06:40 -04:00
AP_SUBGROUPINFO ( rc_channels , " RC " , 17 , ParametersG2 , RC_Channels ) ,
2017-03-14 06:47:18 -03:00
2017-03-01 07:18:11 -04:00
# if VISUAL_ODOMETRY_ENABLED == ENABLED
// @Group: VISO
// @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp
AP_SUBGROUPINFO ( visual_odom , " VISO " , 18 , ParametersG2 , AP_VisualOdom ) ,
# endif
2017-04-13 00:20:12 -03:00
// @Group: TCAL
// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp
AP_SUBGROUPINFO ( temp_calibration , " TCAL " , 19 , ParametersG2 , AP_TempCalibration ) ,
2018-01-18 02:49:20 -04:00
# if TOY_MODE_ENABLED == ENABLED
// @Group: TMODE
// @Path: toy_mode.cpp
AP_SUBGROUPINFO ( toy_mode , " TMODE " , 20 , ParametersG2 , ToyMode ) ,
# endif
2017-07-26 14:14:40 -03:00
2018-02-21 23:58:28 -04:00
# if MODE_SMARTRTL_ENABLED == ENABLED
2017-09-08 23:45:31 -03:00
// @Group: SRTL_
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
AP_SUBGROUPINFO ( smart_rtl , " SRTL_ " , 21 , ParametersG2 , AP_SmartRTL ) ,
2018-02-21 23:58:28 -04:00
# endif
2017-07-26 14:14:40 -03:00
2018-02-10 10:23:06 -04:00
# if WINCH_ENABLED == ENABLED
2017-10-04 23:21:23 -03:00
// @Group: WENC
// @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
AP_SUBGROUPINFO ( wheel_encoder , " WENC " , 22 , ParametersG2 , AP_WheelEncoder ) ,
// @Group: WINCH_
// @Path: ../libraries/AP_Winch/AP_Winch.cpp
AP_SUBGROUPINFO ( winch , " WINCH " , 23 , ParametersG2 , AP_Winch ) ,
2018-02-10 10:23:06 -04:00
# endif
2017-10-04 23:21:23 -03:00
2017-11-08 09:25:53 -04:00
// @Param: PILOT_SPEED_DN
// @DisplayName: Pilot maximum vertical speed descending
// @Description: The maximum vertical descending velocity the pilot may request in cm/s
// @Units: cm/s
// @Range: 50 500
// @Increment: 10
// @User: Standard
AP_GROUPINFO ( " PILOT_SPEED_DN " , 24 , ParametersG2 , pilot_speed_dn , 0 ) ,
2018-01-23 08:33:24 -04:00
// @Param: LAND_ALT_LOW
// @DisplayName: Land alt low
// @Description: Altitude during Landing at which vehicle slows to LAND_SPEED
// @Units: cm
// @Range: 100 10000
// @Increment: 10
// @User: Advanced
AP_GROUPINFO ( " LAND_ALT_LOW " , 25 , ParametersG2 , land_alt_low , 1000 ) ,
2018-02-11 23:26:09 -04:00
# if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
2018-02-07 22:21:09 -04:00
// @Group: FHLD
// @Path: mode_flowhold.cpp
AP_SUBGROUPPTR ( mode_flowhold_ptr , " FHLD " , 26 , ParametersG2 , Copter : : ModeFlowHold ) ,
# endif
2016-06-04 23:37:55 -03:00
AP_GROUPEND
} ;
2016-08-16 07:23:27 -03:00
/*
constructor for g2 object
*/
ParametersG2 : : ParametersG2 ( void )
2018-02-22 00:53:20 -04:00
: temp_calibration ( copter . barometer , copter . ins )
# if BEACON_ENABLED == ENABLED
, beacon ( copter . serial_manager )
# endif
2017-01-02 20:36:26 -04:00
# if PROXIMITY_ENABLED == ENABLED
, proximity ( copter . serial_manager )
# endif
2016-08-25 09:19:31 -03:00
# if ADVANCED_FAILSAFE == ENABLED
2017-01-06 21:06:40 -04:00
, afs ( copter . mission , copter . barometer , copter . gps , copter . rcmap )
2016-08-16 07:23:27 -03:00
# endif
2018-02-21 23:58:28 -04:00
# if MODE_SMARTRTL_ENABLED == ENABLED
2017-09-08 23:45:31 -03:00
, smart_rtl ( copter . ahrs )
2018-02-21 23:58:28 -04:00
# endif
2018-02-11 23:26:09 -04:00
# if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED
2018-02-07 22:21:09 -04:00
, mode_flowhold_ptr ( & copter . mode_flowhold )
# endif
2016-08-16 07:23:27 -03:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
2016-06-04 23:37:55 -03:00
2013-10-01 10:34:44 -03:00
/*
This is a conversion table from old parameter values to new
parameter names . The startup code looks for saved values of the old
parameters and will copy them across to the new parameters if the
new parameter does not yet have a saved value . It then saves the new
value .
Note that this works even if the old parameter has been removed . It
relies on the old k_param index not being removed
The second column below is the index in the var_info [ ] table for the
old object . This should be zero for top level parameters .
*/
2015-10-25 14:03:46 -03:00
const AP_Param : : ConversionInfo conversion_table [ ] = {
2013-10-01 10:34:44 -03:00
{ Parameters : : k_param_battery_monitoring , 0 , AP_PARAM_INT8 , " BATT_MONITOR " } ,
{ Parameters : : k_param_battery_volt_pin , 0 , AP_PARAM_INT8 , " BATT_VOLT_PIN " } ,
{ Parameters : : k_param_battery_curr_pin , 0 , AP_PARAM_INT8 , " BATT_CURR_PIN " } ,
{ Parameters : : k_param_volt_div_ratio , 0 , AP_PARAM_FLOAT , " BATT_VOLT_MULT " } ,
{ Parameters : : k_param_curr_amp_per_volt , 0 , AP_PARAM_FLOAT , " BATT_AMP_PERVOLT " } ,
{ Parameters : : k_param_pack_capacity , 0 , AP_PARAM_INT32 , " BATT_CAPACITY " } ,
2014-10-16 21:37:49 -03:00
{ Parameters : : k_param_log_bitmask_old , 0 , AP_PARAM_INT16 , " LOG_BITMASK " } ,
2015-01-19 09:52:54 -04:00
{ Parameters : : k_param_serial0_baud , 0 , AP_PARAM_INT16 , " SERIAL0_BAUD " } ,
{ Parameters : : k_param_serial1_baud , 0 , AP_PARAM_INT16 , " SERIAL1_BAUD " } ,
{ Parameters : : k_param_serial2_baud , 0 , AP_PARAM_INT16 , " SERIAL2_BAUD " } ,
2016-09-22 20:59:14 -03:00
{ Parameters : : k_param_arming_check_old , 0 , AP_PARAM_INT8 , " ARMING_CHECK " } ,
2013-10-01 10:34:44 -03:00
} ;
2012-02-12 07:26:36 -04:00
2015-05-29 23:12:49 -03:00
void Copter : : load_parameters ( void )
2012-02-12 07:26:36 -04:00
{
2014-01-30 22:10:00 -04:00
if ( ! AP_Param : : check_var_info ( ) ) {
2017-08-11 01:08:41 -03:00
hal . console - > printf ( " Bad var table \n " ) ;
2015-11-19 23:04:45 -04:00
AP_HAL : : panic ( " Bad var table " ) ;
2014-01-30 22:10:00 -04:00
}
2013-05-06 01:32:11 -03:00
// disable centrifugal force correction, it will be enabled as part of the arming process
ahrs . set_correct_centrifugal ( false ) ;
2015-01-28 19:18:20 -04:00
hal . util - > set_soft_armed ( false ) ;
2012-08-21 23:19:50 -03:00
if ( ! g . format_version . load ( ) | |
g . format_version ! = Parameters : : k_format_version ) {
// erase all parameters
2017-08-11 01:08:41 -03:00
hal . console - > printf ( " Firmware change: erasing EEPROM... \n " ) ;
2012-08-21 23:19:50 -03:00
AP_Param : : erase_all ( ) ;
// save the current format version
g . format_version . set_and_save ( Parameters : : k_format_version ) ;
2017-08-11 01:08:41 -03:00
hal . console - > printf ( " done. \n " ) ;
2012-08-21 23:19:50 -03:00
}
2016-01-06 18:32:27 -04:00
uint32_t before = micros ( ) ;
// Load all auto-loaded EEPROM variables
2017-01-09 05:54:18 -04:00
AP_Param : : load_all ( false ) ;
2016-01-06 18:32:27 -04:00
AP_Param : : convert_old_parameters ( & conversion_table [ 0 ] , ARRAY_SIZE ( conversion_table ) ) ;
2017-08-11 01:08:41 -03:00
hal . console - > printf ( " load_all took %uus \n " , ( unsigned ) ( micros ( ) - before ) ) ;
2016-02-16 22:34:31 -04:00
2017-02-07 19:47:36 -04:00
// setup AP_Param frame type flags
AP_Param : : set_frame_type_flags ( AP_PARAM_FRAME_COPTER ) ;
2016-02-16 22:34:31 -04:00
}
// handle conversion of PID gains from Copter-3.3 to Copter-3.4
void Copter : : convert_pid_parameters ( void )
{
// conversion info
2017-01-10 01:30:03 -04:00
const AP_Param : : ConversionInfo pid_conversion_info [ ] = {
2016-02-16 22:34:31 -04:00
{ Parameters : : k_param_pid_rate_roll , 0 , AP_PARAM_FLOAT , " ATC_RAT_RLL_P " } ,
{ Parameters : : k_param_pid_rate_roll , 1 , AP_PARAM_FLOAT , " ATC_RAT_RLL_I " } ,
{ Parameters : : k_param_pid_rate_roll , 2 , AP_PARAM_FLOAT , " ATC_RAT_RLL_D " } ,
{ Parameters : : k_param_pid_rate_pitch , 0 , AP_PARAM_FLOAT , " ATC_RAT_PIT_P " } ,
{ Parameters : : k_param_pid_rate_pitch , 1 , AP_PARAM_FLOAT , " ATC_RAT_PIT_I " } ,
{ Parameters : : k_param_pid_rate_pitch , 2 , AP_PARAM_FLOAT , " ATC_RAT_PIT_D " } ,
{ Parameters : : k_param_pid_rate_yaw , 0 , AP_PARAM_FLOAT , " ATC_RAT_YAW_P " } ,
{ Parameters : : k_param_pid_rate_yaw , 1 , AP_PARAM_FLOAT , " ATC_RAT_YAW_I " } ,
{ Parameters : : k_param_pid_rate_yaw , 2 , AP_PARAM_FLOAT , " ATC_RAT_YAW_D " } ,
2016-05-12 04:34:36 -03:00
# if FRAME_CONFIG == HELI_FRAME
{ Parameters : : k_param_pid_rate_roll , 4 , AP_PARAM_FLOAT , " ATC_RAT_RLL_VFF " } ,
{ Parameters : : k_param_pid_rate_pitch , 4 , AP_PARAM_FLOAT , " ATC_RAT_PIT_VFF " } ,
{ Parameters : : k_param_pid_rate_yaw , 4 , AP_PARAM_FLOAT , " ATC_RAT_YAW_VFF " } ,
# endif
2016-02-16 22:34:31 -04:00
} ;
2017-01-10 01:30:03 -04:00
const AP_Param : : ConversionInfo imax_conversion_info [ ] = {
2016-02-16 22:34:31 -04:00
{ Parameters : : k_param_pid_rate_roll , 5 , AP_PARAM_FLOAT , " ATC_RAT_RLL_IMAX " } ,
{ Parameters : : k_param_pid_rate_pitch , 5 , AP_PARAM_FLOAT , " ATC_RAT_PIT_IMAX " } ,
2016-05-12 04:34:36 -03:00
{ Parameters : : k_param_pid_rate_yaw , 5 , AP_PARAM_FLOAT , " ATC_RAT_YAW_IMAX " } ,
# if FRAME_CONFIG == HELI_FRAME
{ Parameters : : k_param_pid_rate_roll , 7 , AP_PARAM_FLOAT , " ATC_RAT_RLL_ILMI " } ,
{ Parameters : : k_param_pid_rate_pitch , 7 , AP_PARAM_FLOAT , " ATC_RAT_PIT_ILMI " } ,
{ Parameters : : k_param_pid_rate_yaw , 7 , AP_PARAM_FLOAT , " ATC_RAT_YAW_ILMI " } ,
# endif
2016-02-16 22:34:31 -04:00
} ;
2017-01-10 01:30:03 -04:00
const AP_Param : : ConversionInfo angle_and_filt_conversion_info [ ] = {
2016-05-28 03:44:27 -03:00
{ Parameters : : k_param_p_stabilize_roll , 0 , AP_PARAM_FLOAT , " ATC_ANG_RLL_P " } ,
{ Parameters : : k_param_p_stabilize_pitch , 0 , AP_PARAM_FLOAT , " ATC_ANG_PIT_P " } ,
{ Parameters : : k_param_p_stabilize_yaw , 0 , AP_PARAM_FLOAT , " ATC_ANG_YAW_P " } ,
2016-02-16 22:34:31 -04:00
{ Parameters : : k_param_pid_rate_roll , 6 , AP_PARAM_FLOAT , " ATC_RAT_RLL_FILT " } ,
{ Parameters : : k_param_pid_rate_pitch , 6 , AP_PARAM_FLOAT , " ATC_RAT_PIT_FILT " } ,
2017-11-20 07:26:32 -04:00
{ Parameters : : k_param_pid_rate_yaw , 6 , AP_PARAM_FLOAT , " ATC_RAT_YAW_FILT " } ,
{ Parameters : : k_param_pi_vel_xy , 0 , AP_PARAM_FLOAT , " PSC_VELXY_P " } ,
{ Parameters : : k_param_pi_vel_xy , 1 , AP_PARAM_FLOAT , " PSC_VELXY_I " } ,
{ Parameters : : k_param_pi_vel_xy , 2 , AP_PARAM_FLOAT , " PSC_VELXY_IMAX " } ,
{ Parameters : : k_param_pi_vel_xy , 3 , AP_PARAM_FLOAT , " PSC_VELXY_FILT " } ,
2017-11-20 21:49:11 -04:00
{ Parameters : : k_param_p_vel_z , 0 , AP_PARAM_FLOAT , " PSC_VELZ_P " } ,
2018-01-27 02:40:46 -04:00
{ Parameters : : k_param_pid_accel_z , 0 , AP_PARAM_FLOAT , " PSC_ACCZ_P " } ,
{ Parameters : : k_param_pid_accel_z , 1 , AP_PARAM_FLOAT , " PSC_ACCZ_I " } ,
{ Parameters : : k_param_pid_accel_z , 2 , AP_PARAM_FLOAT , " PSC_ACCZ_D " } ,
{ Parameters : : k_param_pid_accel_z , 5 , AP_PARAM_FLOAT , " PSC_ACCZ_IMAX " } ,
{ Parameters : : k_param_pid_accel_z , 6 , AP_PARAM_FLOAT , " PSC_ACCZ_FILT " } ,
2017-11-20 21:49:11 -04:00
{ Parameters : : k_param_p_alt_hold , 0 , AP_PARAM_FLOAT , " PSC_POSZ_P " } ,
{ Parameters : : k_param_p_pos_xy , 0 , AP_PARAM_FLOAT , " PSC_POSXY_P " } ,
2016-02-16 22:34:31 -04:00
} ;
2017-01-10 01:30:03 -04:00
const AP_Param : : ConversionInfo throttle_conversion_info [ ] = {
2016-06-04 01:32:34 -03:00
{ Parameters : : k_param_throttle_min , 0 , AP_PARAM_FLOAT , " MOT_SPIN_MIN " } ,
{ Parameters : : k_param_throttle_mid , 0 , AP_PARAM_FLOAT , " MOT_THST_HOVER " }
} ;
2016-02-16 22:34:31 -04:00
// gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees
// and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500
float pid_scaler = 1.27f ;
2017-01-09 05:54:18 -04:00
# if FRAME_CONFIG != HELI_FRAME
2016-02-16 22:34:31 -04:00
// Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation
2016-12-14 21:26:36 -04:00
if ( g . frame_type = = AP_Motors : : MOTOR_FRAME_TYPE_X | | g . frame_type = = AP_Motors : : MOTOR_FRAME_TYPE_V | | g . frame_type = = AP_Motors : : MOTOR_FRAME_TYPE_H ) {
2016-02-16 22:34:31 -04:00
pid_scaler = 0.9f ;
}
# endif
// scale PID gains
uint8_t table_size = ARRAY_SIZE ( pid_conversion_info ) ;
for ( uint8_t i = 0 ; i < table_size ; i + + ) {
AP_Param : : convert_old_parameter ( & pid_conversion_info [ i ] , pid_scaler ) ;
}
// reduce IMAX into -1 ~ +1 range
table_size = ARRAY_SIZE ( imax_conversion_info ) ;
for ( uint8_t i = 0 ; i < table_size ; i + + ) {
AP_Param : : convert_old_parameter ( & imax_conversion_info [ i ] , 1.0f / 4500.0f ) ;
}
2016-05-28 03:44:27 -03:00
// convert angle controller gain and filter without scaling
table_size = ARRAY_SIZE ( angle_and_filt_conversion_info ) ;
2016-02-16 22:34:31 -04:00
for ( uint8_t i = 0 ; i < table_size ; i + + ) {
2016-05-28 03:44:27 -03:00
AP_Param : : convert_old_parameter ( & angle_and_filt_conversion_info [ i ] , 1.0f ) ;
2016-02-16 22:34:31 -04:00
}
2016-06-04 01:32:34 -03:00
// convert throttle parameters (multicopter only)
table_size = ARRAY_SIZE ( throttle_conversion_info ) ;
for ( uint8_t i = 0 ; i < table_size ; i + + ) {
AP_Param : : convert_old_parameter ( & throttle_conversion_info [ i ] , 0.001f ) ;
}
2017-01-08 21:48:13 -04:00
const uint8_t old_rc_keys [ 14 ] = { Parameters : : k_param_rc_1_old , Parameters : : k_param_rc_2_old ,
Parameters : : k_param_rc_3_old , Parameters : : k_param_rc_4_old ,
Parameters : : k_param_rc_5_old , Parameters : : k_param_rc_6_old ,
Parameters : : k_param_rc_7_old , Parameters : : k_param_rc_8_old ,
Parameters : : k_param_rc_9_old , Parameters : : k_param_rc_10_old ,
Parameters : : k_param_rc_11_old , Parameters : : k_param_rc_12_old ,
Parameters : : k_param_rc_13_old , Parameters : : k_param_rc_14_old } ;
const uint16_t old_aux_chan_mask = 0x3FF0 ;
// note that we don't pass in rcmap as we don't want output channel functions changed based on rcmap
2017-01-10 01:09:58 -04:00
if ( SRV_Channels : : upgrade_parameters ( old_rc_keys , old_aux_chan_mask , nullptr ) ) {
2017-01-10 02:48:51 -04:00
// the rest needs to be done after motors allocation
upgrading_frame_params = true ;
2017-01-10 01:09:58 -04:00
}
2012-02-12 07:26:36 -04:00
}