2013-05-29 20:55:51 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
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} }
# 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
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)
2014-10-14 00:42:14 -03:00
// @Values: 0:ArduPlane,4:AntennaTracker,10:Copter,20:Rover
2012-12-10 08:45:57 -04:00
// @User: Advanced
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-03-09 00:18:16 -03:00
# if CLI_ENABLED == ENABLED
// @Param: CLI_ENABLED
// @DisplayName: CLI Enable
// @Description: This enables/disables the checking for three carriage returns on telemetry links on startup to enter the diagnostics command line interface
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR ( cli_enabled , " CLI_ENABLED " , 0 ) ,
# endif
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
// @Units: Centimeters
// @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
2015-08-13 14:40:26 -03:00
// @Range: 0.0 500.0
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
// @Description: Bits for: Feedback starts from mid stick
// @User: Standard
// @Values: 0:None,1:FeedbackFromMid
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
2012-08-29 20:03:01 -03:00
// @Units: seconds
// @Range: 0 10
// @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
2012-11-29 08:08:19 -04:00
// @Description: The minimum altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
2012-12-10 08:45:57 -04:00
// @Units: Centimeters
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 ) ,
2012-08-21 23:19:50 -03:00
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
2014-07-16 16:15:31 -03:00
GSCALAR ( sonar_gain , " RNGFND_GAIN " , SONAR_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
2013-11-16 01:46:57 -04:00
// @Values: 0:Disabled,1:Land,2:RTL
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
2013-10-01 10:34:44 -03:00
// @Units: Volts
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
2013-10-01 10:34:44 -03:00
// @Units: mAh
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.
2013-04-29 09:30:22 -03:00
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode
// @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.
2012-12-10 08:45:57 -04:00
// @Units: Centimeters
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
// @Units: Centimeters
// @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 ) ,
2012-12-21 23:52:49 -04:00
// @Param: PILOT_VELZ_MAX
// @DisplayName: Pilot maximum vertical speed
// @Description: The maximum vertical velocity the pilot may request in cm/s
// @Units: Centimeters/Second
2014-04-30 00:05:02 -03:00
// @Range: 50 500
2012-12-21 23:52:49 -04:00
// @Increment: 10
// @User: Standard
GSCALAR ( pilot_velocity_z_max , " PILOT_VELZ_MAX " , PILOT_VELZ_MAX ) ,
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-07-05 03:33:40 -03:00
// @Param: THR_MIN
2013-11-26 09:35:11 -04:00
// @DisplayName: Throttle Minimum
2012-12-10 08:45:57 -04:00
// @Description: The minimum throttle that will be sent to the motors to keep them spinning
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-09-12 10:45:18 -03:00
// @Range: 0 300
2012-08-21 23:19:50 -03:00
// @Increment: 1
// @User: Standard
2013-10-13 08:41:11 -03:00
GSCALAR ( throttle_min , " THR_MIN " , THR_MIN_DEFAULT ) ,
2012-07-05 03:33:40 -03:00
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
2013-05-01 21:39:44 -03:00
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always LAND
2012-08-21 23:19:50 -03:00
// @User: Standard
2012-12-10 10:38:43 -04:00
GSCALAR ( failsafe_throttle , " FS_THR_ENABLE " , FS_THR_DISABLED ) ,
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
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers
2013-06-18 03:56:39 -03:00
// @Range: 925 1100
2013-10-21 08:33:56 -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-01-30 11:25:41 -04:00
// @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
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-01-30 11:25:41 -04:00
// @Increment: 1
2013-10-13 08:41:11 -03:00
GSCALAR ( throttle_mid , " THR_MID " , THR_MID_DEFAULT ) ,
2013-01-30 11:25:41 -04:00
2013-10-27 10:13:42 -03:00
// @Param: THR_DZ
// @DisplayName: Throttle deadzone
// @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
// @User: Standard
// @Range: 0 300
// @Units: pwm
// @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
2015-07-01 23:59:56 -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
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
2015-07-01 23:59:56 -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
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
2015-07-01 23:59:56 -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
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
2015-07-01 23:59:56 -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
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
2015-07-01 23:59:56 -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
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
2015-07-01 23:59:56 -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
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
// @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
2015-06-11 04:13:15 -03:00
// @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131070:All+DisarmedLogging,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled
2015-05-30 21:16:44 -03:00
// @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,16:WHEN_DISARMED,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
2015-07-12 21:21:32 -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, 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
2015-04-28 02:00:24 -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,14:Altitude Hold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,42:Loiter Speed,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,13:Heli Ext Gyro,17:OF Loiter kP,18:OF Loiter kI,19:OF Loiter kD,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
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
// @Param: FRAME
2013-01-14 02:49:26 -04:00
// @DisplayName: Frame Orientation (+, X or V)
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
2014-08-18 02:25:37 -03:00
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B (New)
2012-12-10 08:45:57 -04:00
// @User: Standard
2014-01-21 08:44:17 -04:00
GSCALAR ( frame_orientation , " FRAME " , AP_MOTORS_X_FRAME ) ,
2012-12-06 04:40:36 -04:00
// @Param: CH7_OPT
// @DisplayName: Channel 7 option
2012-12-10 08:45:57 -04:00
// @Description: Select which function if performed when CH7 is above 1800 pwm
2015-05-17 00:22:47 -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, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake
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
// @Description: Select which function if performed when CH8 is above 1800 pwm
2015-05-17 00:22:47 -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, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake
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
// @Description: Select which function if performed when CH9 is above 1800 pwm
2015-05-17 00:22:47 -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, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake
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
// @Description: Select which function if performed when CH10 is above 1800 pwm
2015-05-17 00:22:47 -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, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake
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
// @Description: Select which function if performed when CH11 is above 1800 pwm
2015-05-17 00:22:47 -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, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake
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
// @Description: Select which function if performed when CH12 is above 1800 pwm
2015-05-17 00:22:47 -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, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 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, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake
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
2013-05-20 02:48:04 -03:00
// @Param: ARMING_CHECK
// @DisplayName: Arming check
2013-11-15 04:12:31 -04:00
// @Description: Allows enabling or disabling of pre-arming checks of receiver, accelerometer, barometer, compass and GPS
2015-04-23 23:12:03 -03:00
// @Values: 0:Disabled, 1:Enabled, -3:Skip Baro, -5:Skip Compass, -9:Skip GPS, -17:Skip INS, -33:Skip Params/Sonar, -65:Skip RC, 127:Skip Voltage
2015-06-27 07:18:05 -03:00
// @Bitmask: 0:All,1:Baro,2:Compass,3:GPS,4:INS,5:Parameters+Sonar,6:RC,7:Voltage
2013-05-20 02:48:04 -03:00
// @User: Standard
2013-11-25 04:23:39 -04:00
GSCALAR ( arming_check , " ARMING_CHECK " , ARMING_CHECK_ALL ) ,
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.
// @Units: Seconds
// @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
2014-10-14 00:42:14 -03:00
// @Units: Centi-degrees
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
// @Increment: 1
// @User: Standard
2014-02-12 03:28:41 -04:00
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
2015-06-02 23:37:54 -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
# if POSHOLD_ENABLED == ENABLED
// @Param: PHLD_BRAKE_RATE
// @DisplayName: PosHold braking rate
// @Description: PosHold flight mode's rotation rate during braking in deg/sec
2014-10-14 00:42:14 -03:00
// @Units: deg/sec
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
2014-04-11 05:15:09 -03:00
// @Units: Centi-degrees
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-23 03:24:03 -03:00
# endif
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 ) ,
2012-08-21 23:19:50 -03:00
# if FRAME_CONFIG == HELI_FRAME
2013-05-21 03:33:41 -03:00
// @Group: HS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2012-08-21 23:19:50 -03:00
GGROUP ( heli_servo_1 , " HS1_ " , RC_Channel ) ,
2013-05-21 03:33:41 -03:00
// @Group: HS2_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2012-08-21 23:19:50 -03:00
GGROUP ( heli_servo_2 , " HS2_ " , RC_Channel ) ,
2013-05-21 03:33:41 -03:00
// @Group: HS3_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2012-08-21 23:19:50 -03:00
GGROUP ( heli_servo_3 , " HS3_ " , RC_Channel ) ,
2013-05-21 03:33:41 -03:00
// @Group: HS4_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2012-08-21 23:19:50 -03:00
GGROUP ( heli_servo_4 , " HS4_ " , RC_Channel ) ,
2015-07-27 21:01:55 -03:00
// @Group: H_RSC_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( heli_servo_rsc , " H_RSC_ " , RC_Channel ) ,
2013-05-21 03:33:41 -03:00
2014-01-09 18:02:08 -04:00
// @Param: H_STAB_COL_MIN
2013-11-09 01:25:06 -04:00
// @DisplayName: Heli Stabilize Throttle Collective Minimum
// @Description: Helicopter's minimum collective position while pilot directly controls collective in stabilize mode
// @Range: 0 500
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-11-09 01:25:06 -04:00
// @Increment: 1
// @User: Standard
2014-01-09 18:02:08 -04:00
GSCALAR ( heli_stab_col_min , " H_STAB_COL_MIN " , HELI_STAB_COLLECTIVE_MIN_DEFAULT ) ,
2013-11-09 01:25:06 -04:00
2014-01-09 18:02:08 -04:00
// @Param: H_STAB_COL_MAX
2013-11-09 01:25:06 -04:00
// @DisplayName: Stabilize Throttle Maximum
// @Description: Helicopter's maximum collective position while pilot directly controls collective in stabilize mode
// @Range: 500 1000
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-11-09 01:25:06 -04:00
// @Increment: 1
// @User: Standard
2014-01-09 18:02:08 -04:00
GSCALAR ( heli_stab_col_max , " H_STAB_COL_MAX " , HELI_STAB_COLLECTIVE_MAX_DEFAULT ) ,
2012-08-21 23:19:50 -03:00
# endif
2013-11-09 01:25:06 -04:00
2012-08-21 23:19:50 -03:00
// 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_
2013-01-02 05:40:59 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2012-09-02 00:51:23 -03:00
GGROUP ( rc_5 , " RC5_ " , RC_Channel_aux ) ,
2012-08-21 23:19:50 -03:00
// @Group: RC6_
2013-01-02 05:40:59 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2012-09-02 00:51:23 -03:00
GGROUP ( rc_6 , " RC6_ " , RC_Channel_aux ) ,
2012-08-21 23:19:50 -03:00
// @Group: RC7_
2013-01-02 05:40:59 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2012-09-02 00:51:23 -03:00
GGROUP ( rc_7 , " RC7_ " , RC_Channel_aux ) ,
2012-08-21 23:19:50 -03:00
// @Group: RC8_
2013-01-02 05:40:59 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2012-09-02 00:51:23 -03:00
GGROUP ( rc_8 , " RC8_ " , RC_Channel_aux ) ,
2012-07-10 19:39:13 -03:00
2014-03-31 14:57:45 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
2013-10-31 10:52:13 -03:00
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_9 , " RC9_ " , RC_Channel_aux ) ,
# endif
2012-08-21 23:19:50 -03:00
// @Group: RC10_
2013-01-02 05:40:59 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2012-08-21 23:19:50 -03:00
GGROUP ( rc_10 , " RC10_ " , RC_Channel_aux ) ,
// @Group: RC11_
2013-01-02 05:40:59 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2012-08-21 23:19:50 -03:00
GGROUP ( rc_11 , " RC11_ " , RC_Channel_aux ) ,
2012-06-29 18:34:40 -03:00
2014-03-31 14:57:45 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
2013-04-25 07:01:34 -03:00
// @Group: RC12_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_12 , " RC12_ " , RC_Channel_aux ) ,
2014-03-25 00:41:51 -03:00
// @Group: RC13_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_13 , " RC13_ " , RC_Channel_aux ) ,
// @Group: RC14_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_14 , " RC14_ " , RC_Channel_aux ) ,
2013-04-25 07:01:34 -03:00
# endif
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
2014-08-12 23:25:59 -03:00
// @Param: ACRO_EXPO
// @DisplayName: Acro Expo
// @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
2014-08-12 23:25:59 -03:00
// @User: Advanced
GSCALAR ( acro_expo , " ACRO_EXPO " , ACRO_EXPO_DEFAULT ) ,
2012-08-21 23:19:50 -03:00
// PID controller
//---------------
2014-05-02 18:44:09 -03:00
2013-01-02 04:05:57 -04:00
// @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
2015-04-09 08:09:03 -03:00
// @Range: 0.08 0.30
2013-06-16 09:53:50 -03:00
// @Increment: 0.005
2013-01-02 04:05:57 -04:00
// @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
2013-01-02 04:20:58 -04:00
// @Range: 0.01 0.5
2013-06-16 09:53:50 -03:00
// @Increment: 0.01
2013-01-02 04:20:58 -04:00
// @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
2014-08-06 01:24:10 -03:00
// @Range: 0 4500
2013-06-16 09:53:50 -03:00
// @Increment: 10
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-01-02 04:05:57 -04:00
// @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
2013-11-24 23:52:37 -04:00
// @Range: 0.001 0.02
2013-06-16 09:53:50 -03:00
// @Increment: 0.001
2013-01-02 04:05:57 -04:00
// @User: Standard
2014-05-02 18:44:09 -03:00
# if FRAME_CONFIG == HELI_FRAME
GGROUP ( pid_rate_roll , " RATE_RLL_ " , AC_HELI_PID ) ,
# else
2012-08-21 23:19:50 -03:00
GGROUP ( pid_rate_roll , " RATE_RLL_ " , AC_PID ) ,
2014-05-02 18:44:09 -03:00
# endif
2013-01-02 04:05:57 -04:00
// @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
2015-04-09 08:09:03 -03:00
// @Range: 0.08 0.30
2013-06-16 09:53:50 -03:00
// @Increment: 0.005
2013-01-02 04:05:57 -04:00
// @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
2013-01-02 04:20:58 -04:00
// @Range: 0.01 0.5
2013-06-16 09:53:50 -03:00
// @Increment: 0.01
2013-01-02 04:20:58 -04:00
// @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
2014-08-06 01:24:10 -03:00
// @Range: 0 4500
2013-06-16 09:53:50 -03:00
// @Increment: 10
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-01-02 04:05:57 -04:00
// @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
2013-11-24 23:52:37 -04:00
// @Range: 0.001 0.02
2013-06-16 09:53:50 -03:00
// @Increment: 0.001
2013-01-02 04:05:57 -04:00
// @User: Standard
2014-05-02 18:44:09 -03:00
# if FRAME_CONFIG == HELI_FRAME
GGROUP ( pid_rate_pitch , " RATE_PIT_ " , AC_HELI_PID ) ,
# else
2012-08-21 23:19:50 -03:00
GGROUP ( pid_rate_pitch , " RATE_PIT_ " , AC_PID ) ,
2014-05-02 18:44:09 -03:00
# endif
2012-08-21 23:19:50 -03:00
2013-01-02 04:05:57 -04:00
// @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
2014-09-10 04:40:36 -03:00
// @Range: 0.150 0.50
2013-06-16 09:53:50 -03:00
// @Increment: 0.005
2013-01-02 04:05:57 -04:00
// @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
2014-09-10 04:40:36 -03:00
// @Range: 0.010 0.05
2013-06-16 09:53:50 -03:00
// @Increment: 0.01
2013-01-02 04:20:58 -04:00
// @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
2014-08-06 01:24:10 -03:00
// @Range: 0 4500
2013-06-16 09:53:50 -03:00
// @Increment: 10
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-01-02 04:05:57 -04:00
// @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
2013-11-24 23:52:37 -04:00
// @Range: 0.000 0.02
2013-06-16 09:53:50 -03:00
// @Increment: 0.001
2013-01-02 04:05:57 -04:00
// @User: Standard
2014-05-02 18:44:09 -03:00
# if FRAME_CONFIG == HELI_FRAME
GGROUP ( pid_rate_yaw , " RATE_YAW_ " , AC_HELI_PID ) ,
# else
2013-01-02 04:05:57 -04:00
GGROUP ( pid_rate_yaw , " RATE_YAW_ " , AC_PID ) ,
2014-05-02 18:44:09 -03:00
# endif
2012-08-21 23:19:50 -03:00
2015-01-29 02:51:21 -04:00
// @Param: VEL_XY_P
// @DisplayName: Velocity (horizontal) P gain
// @Description: Velocity (horizontal) P gain. Converts the difference between desired velocity to a target acceleration
2013-06-16 09:53:50 -03:00
// @Range: 0.1 6.0
// @Increment: 0.1
2013-11-26 09:17:02 -04:00
// @User: Advanced
2013-01-02 04:20:58 -04:00
2015-01-29 02:51:21 -04:00
// @Param: VEL_XY_I
// @DisplayName: Velocity (horizontal) I gain
// @Description: Velocity (horizontal) I gain. Corrects long-term difference in desired velocity to a target acceleration
2013-06-16 09:53:50 -03:00
// @Range: 0.02 1.00
// @Increment: 0.01
2013-11-26 09:17:02 -04:00
// @User: Advanced
2013-01-02 04:20:58 -04:00
2015-01-29 02:51:21 -04:00
// @Param: VEL_XY_IMAX
// @DisplayName: Velocity (horizontal) integrator maximum
// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
2013-01-02 04:20:58 -04:00
// @Range: 0 4500
2013-06-16 09:53:50 -03:00
// @Increment: 10
2015-01-29 02:51:21 -04:00
// @Units: cm/s/s
2013-11-26 09:17:02 -04:00
// @User: Advanced
2015-01-29 02:51:21 -04:00
GGROUP ( pi_vel_xy , " VEL_XY_ " , AC_PI_2D ) ,
2012-08-21 23:19:50 -03:00
2015-01-31 02:49:17 -04:00
// @Param: VEL_Z_P
// @DisplayName: Velocity (vertical) P gain
// @Description: Velocity (vertical) P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
2013-01-02 04:44:21 -04:00
// @Range: 1.000 8.000
// @User: Standard
2015-01-31 02:49:17 -04:00
GGROUP ( p_vel_z , " VEL_Z_ " , AC_P ) ,
2013-01-02 04:44:21 -04:00
2015-01-31 02:49:17 -04:00
// @Param: ACCEL_Z_P
2013-01-02 04:44:21 -04:00
// @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
2015-01-31 02:49:17 -04:00
// @Param: ACCEL_Z_I
2013-01-02 04:44:21 -04:00
// @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
2015-01-31 02:49:17 -04:00
// @Param: ACCEL_Z_IMAX
2013-01-02 04:44:21 -04:00
// @DisplayName: Throttle acceleration controller I gain maximum
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
2014-09-12 02:02:06 -03:00
// @Range: 0 1000
2013-11-26 09:35:11 -04:00
// @Units: Percent*10
2013-01-02 04:44:21 -04:00
// @User: Standard
2015-01-31 02:49:17 -04:00
// @Param: ACCEL_Z_D
2013-01-02 04:44:21 -04:00
// @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
2015-08-25 23:14:58 -03:00
// @Param: ACCEL_Z_FILT_HZ
// @DisplayName: Throttle acceleration filter
// @Description: Filter applied to acceleration to reduce noise. Lower values reduce noise but add delay.
// @Range: 1.000 100.000
// @Units: Hz
// @User: Standard
2015-01-31 02:49:17 -04:00
GGROUP ( pid_accel_z , " ACCEL_Z_ " , AC_PID ) ,
2012-11-23 02:57:49 -04:00
2014-08-06 01:24:10 -03:00
// P controllers
2012-08-21 23:19:50 -03:00
//--------------
2013-01-02 05:32:11 -04:00
// @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
2014-04-20 22:41:01 -03:00
// @Range: 3.000 12.000
2013-01-02 05:32:11 -04:00
// @User: Standard
2014-02-14 03:08:59 -04:00
GGROUP ( p_stabilize_roll , " STB_RLL_ " , AC_P ) ,
2013-01-02 05:32:11 -04:00
// @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
2014-04-20 22:41:01 -03:00
// @Range: 3.000 12.000
2013-01-02 05:32:11 -04:00
// @User: Standard
2014-02-14 03:08:59 -04:00
GGROUP ( p_stabilize_pitch , " STB_PIT_ " , AC_P ) ,
2013-01-02 05:32:11 -04:00
// @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
2014-02-14 03:08:59 -04:00
GGROUP ( p_stabilize_yaw , " STB_YAW_ " , AC_P ) ,
2012-08-21 23:19:50 -03:00
2015-01-31 02:49:17 -04:00
// @Param: POS_Z_P
// @DisplayName: Position (vertical) controller P gain
// @Description: Position (vertical) 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
2013-04-03 10:38:34 -03:00
// @Range: 1.000 3.000
2013-01-02 05:32:11 -04:00
// @User: Standard
2015-01-31 02:49:17 -04:00
GGROUP ( p_alt_hold , " POS_Z_ " , AC_P ) ,
2013-01-02 05:32:11 -04:00
2015-01-31 02:49:17 -04:00
// @Param: POS_XY_P
// @DisplayName: Position (horizonal) controller P gain
2014-02-14 03:08:59 -04:00
// @Description: Loiter 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
2013-10-07 02:45:39 -03:00
// @Range: 0.500 2.000
2013-01-02 05:32:11 -04:00
// @User: Standard
2015-01-31 02:49:17 -04:00
GGROUP ( p_pos_xy , " POS_XY_ " , AC_P ) ,
2012-08-21 23:19:50 -03:00
2015-08-28 05:16:46 -03:00
# if PRECISION_LANDING == ENABLED
// @Param: PRECLNDVEL_P
// @DisplayName: Precision landing velocity controller P gain
// @Description: Precision landing velocity controller P gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: PRECLNDVEL_I
// @DisplayName: Precision landing velocity controller I gain
// @Description: Precision landing velocity controller I gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: PRECLNDVEL_IMAX
// @DisplayName: Precision landing velocity controller I gain maximum
// @Description: Precision landing velocity controller I gain maximum
// @Range: 0 1000
// @Units: cm/s
// @User: Standard
GGROUP ( pi_precland , " PLAND_ " , AC_PI_2D ) ,
# endif
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 ) ,
2013-12-17 00:58:11 -04:00
# if EPM_ENABLED == ENABLED
// @Group: EPM_
// @Path: ../libraries/AP_EPM/AP_EPM.cpp
GOBJECT ( epm , " EPM_ " , AP_EPM ) ,
# endif
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
2012-08-21 23:19:50 -03:00
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/Compass.cpp
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
2013-04-05 06:32:36 -03:00
GOBJECT ( wp_nav , " WPNAV_ " , AC_WPNav ) ,
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
GOBJECT ( circle_nav , " CIRCLE_ " , AC_Circle ) ,
2014-01-29 09:51:08 -04:00
# if FRAME_CONFIG == HELI_FRAME
2014-02-03 03:39:43 -04:00
GOBJECT ( attitude_control , " ATC_ " , AC_AttitudeControl_Heli ) ,
2014-01-29 09:51:08 -04:00
# else
2014-04-24 20:53:03 -03:00
// @Group: ATC_
2014-01-10 10:29:55 -04:00
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
2014-02-03 00:28:13 -04:00
GOBJECT ( attitude_control , " ATC_ " , AC_AttitudeControl ) ,
2014-01-29 09:51:08 -04:00
# endif
2014-01-10 10:29:55 -04:00
// @Group: POSCON_
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
2015-04-16 07:07:17 -03:00
GOBJECT ( 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
2013-11-23 06:45:42 -04:00
GOBJECTN ( gcs [ 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
2013-11-23 06:45:42 -04:00
GOBJECTN ( gcs [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK ) ,
// @Group: SR2_
2015-06-15 20:59:39 -03:00
// @Path: GCS_Mavlink.cpp
2013-11-23 06:45:42 -04:00
GOBJECTN ( gcs [ 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
2015-05-15 01:24:18 -03:00
GOBJECTN ( gcs [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK ) ,
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-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
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
2014-04-06 22:18:43 -03:00
# if AC_RALLY == ENABLED
// @Group: RALLY_
2014-04-19 10:36:18 -03:00
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
2014-04-06 22:18:43 -03:00
GOBJECT ( rally , " RALLY_ " , AP_Rally ) ,
# endif
2012-08-21 23:19:50 -03:00
# if FRAME_CONFIG == HELI_FRAME
// @Group: H_
2015-07-22 11:04:04 -03:00
// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp
GOBJECT ( motors , " H_ " , AP_MotorsHeli_Single ) ,
2013-11-12 09:52:41 -04:00
# elif FRAME_CONFIG == SINGLE_FRAME
// @Group: SS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( single_servo_1 , " SS1_ " , RC_Channel ) ,
// @Group: SS2_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( single_servo_2 , " SS2_ " , RC_Channel ) ,
// @Group: SS3_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( single_servo_3 , " SS3_ " , RC_Channel ) ,
// @Group: SS4_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( single_servo_4 , " SS4_ " , RC_Channel ) ,
2013-11-26 08:50:29 -04:00
// @Group: MOT_
2013-11-19 00:25:53 -04:00
// @Path: ../libraries/AP_Motors/AP_MotorsSingle.cpp
2013-11-12 09:52:41 -04:00
GOBJECT ( motors , " MOT_ " , AP_MotorsSingle ) ,
2014-02-06 08:28:55 -04:00
# elif FRAME_CONFIG == COAX_FRAME
// @Group: SS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( single_servo_1 , " SS1_ " , RC_Channel ) ,
// @Group: SS2_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP ( single_servo_2 , " SS2_ " , RC_Channel ) ,
// @Group: MOT_
2014-02-06 10:41:13 -04:00
// @Path: ../libraries/AP_Motors/AP_MotorsCoax.cpp
GOBJECT ( motors , " MOT_ " , AP_MotorsCoax ) ,
2014-02-06 08:28:55 -04:00
2015-05-14 22:04:41 -03:00
# elif FRAME_CONFIG == TRI_FRAME
// @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_MotorsTri.cpp
GOBJECT ( motors , " MOT_ " , AP_MotorsTri ) ,
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
2015-07-15 07:54:18 -03:00
GOBJECT ( motors , " MOT_ " , AP_MotorsMulticopter ) ,
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 ) ,
2014-02-21 00:51:22 -04:00
// @Group: EKF_
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
2015-06-01 03:16:59 -03:00
GOBJECTN ( EKF , NavEKF , " EKF_ " , NavEKF ) ,
2014-02-21 00:51:22 -04:00
2015-09-21 02:28:04 -03:00
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN ( EKF2 , NavEKF2 , " EK2_ " , NavEKF2 ) ,
2014-02-27 21:15:40 -04:00
// @Group: MIS_
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
GOBJECT ( mission , " MIS_ " , AP_Mission ) ,
2015-08-28 03:00:55 -03:00
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
GOBJECT ( rssi , " RSSI_ " , AP_RSSI ) ,
2014-06-27 01:23:56 -03:00
# if CONFIG_SONAR == 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
2014-07-16 16:15:31 -03:00
GOBJECT ( sonar , " RNGFND " , RangeFinder ) ,
2014-06-27 01:23:56 -03:00
# endif
2014-07-24 18:58:58 -03:00
# if AP_TERRAIN_AVAILABLE
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
// @Group: PRECLAND_
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
GOBJECT ( precland , " PLAND_ " , AC_PrecLand ) ,
# endif
2015-08-07 02:34:56 -03:00
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT ( rpm_sensor , " RPM " , AP_RPM ) ,
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
GSCALAR ( autotune_min_d , " AUTOTUNE_MIN_D " , 0.004f ) ,
2012-08-21 23:19:50 -03:00
AP_VAREND
2012-02-12 07:26:36 -04: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 " } ,
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 ( ) ) {
2015-10-25 17:10:41 -03:00
cliSerial - > printf ( " Bad var table \n " ) ;
2015-10-24 18:45:41 -03:00
hal . scheduler - > 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
2015-10-25 17:10:41 -03:00
cliSerial - > 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 ) ;
2015-10-25 16:50:51 -03:00
cliSerial - > println ( " done. " ) ;
2012-08-21 23:19:50 -03:00
} else {
uint32_t before = micros ( ) ;
// Load all auto-loaded EEPROM variables
AP_Param : : load_all ( ) ;
2015-07-06 12:30:40 -03:00
AP_Param : : convert_old_parameters ( & conversion_table [ 0 ] , ARRAY_SIZE ( conversion_table ) ) ;
2015-10-26 10:02:37 -03:00
cliSerial - > printf ( " load_all took %uus \n " , micros ( ) - before ) ;
2012-08-21 23:19:50 -03:00
}
2012-02-12 07:26:36 -04:00
}