mirror of https://github.com/ArduPilot/ardupilot
Rover: added more parameter docs
This commit is contained in:
parent
92026be9d6
commit
1f8a61615c
|
@ -138,10 +138,10 @@ public:
|
|||
//
|
||||
// 200: Feed-forward gains
|
||||
//
|
||||
k_param_kff_pitch_compensation = 200,
|
||||
k_param_kff_rudder_mix,
|
||||
k_param_kff_pitch_to_throttle,
|
||||
k_param_kff_throttle_to_pitch,
|
||||
k_param_kff_pitch_compensation = 200, // unused
|
||||
k_param_kff_rudder_mix, // unused
|
||||
k_param_kff_pitch_to_throttle, // unused
|
||||
k_param_kff_throttle_to_pitch, // unused
|
||||
|
||||
//
|
||||
// 210: flight modes
|
||||
|
@ -238,13 +238,6 @@ public:
|
|||
AP_Int8 serial3_baud;
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
// Feed-forward gains
|
||||
//
|
||||
AP_Float kff_pitch_compensation;
|
||||
AP_Float kff_rudder_mix;
|
||||
AP_Float kff_pitch_to_throttle;
|
||||
AP_Float kff_throttle_to_pitch;
|
||||
|
||||
// Crosstrack navigation
|
||||
//
|
||||
AP_Float crosstrack_gain;
|
||||
|
|
|
@ -18,38 +18,167 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
|
||||
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
|
||||
// @Param: SERIAL3_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the telemetry port
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
|
||||
// @User: Standard
|
||||
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
|
||||
|
||||
// @Param: TELEM_DELAY
|
||||
// @DisplayName: Telemetry startup delay
|
||||
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
|
||||
// @User: Standard
|
||||
// @Units: seconds
|
||||
// @Range: 0 10
|
||||
// @Increment: 1
|
||||
GSCALAR(telem_delay, "TELEM_DELAY", 0),
|
||||
GSCALAR(kff_pitch_compensation, "KFF_PTCHCOMP", PITCH_COMP),
|
||||
GSCALAR(kff_rudder_mix, "KFF_RDDRMIX", RUDDER_MIX),
|
||||
GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR", P_TO_T),
|
||||
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", T_TO_P),
|
||||
|
||||
// @Param: MANUAL_LEVEL
|
||||
// @DisplayName: Manual Level
|
||||
// @Description: Setting this to Disabled(0) will enable autolevel on every boot. Setting it to Enabled(1) will do a calibration only when you tell it to
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
GSCALAR(manual_level, "MANUAL_LEVEL", 0),
|
||||
|
||||
// @Param: XTRK_GAIN_SC
|
||||
// @DisplayName: Crosstrack Gain
|
||||
// @Description: The scale between distance off the line and angle to meet the line (in Degrees * 100)
|
||||
// @Range: 0 2000
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", XTRACK_GAIN_SCALED),
|
||||
|
||||
// @Param: XTRK_ANGLE_CD
|
||||
// @DisplayName: Crosstrack Entry Angle
|
||||
// @Description: Maximum angle used to correct for track following.
|
||||
// @Units: centi-Degrees
|
||||
// @Range: 0 9000
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD", XTRACK_ENTRY_ANGLE_CENTIDEGREE),
|
||||
|
||||
GSCALAR(command_total, "CMD_TOTAL", 0),
|
||||
GSCALAR(command_index, "CMD_INDEX", 0),
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),
|
||||
|
||||
// @Param: THR_MIN
|
||||
// @DisplayName: Minimum Throttle
|
||||
// @Description: The minimum throttle setting to which the autopilot will apply.
|
||||
// @Units: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
|
||||
|
||||
// @Param: THR_MAX
|
||||
// @DisplayName: Maximum Throttle
|
||||
// @Description: The maximum throttle setting to which the autopilot will apply.
|
||||
// @Units: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
|
||||
|
||||
// @Param: THR_SLEWRATE
|
||||
// @DisplayName: Throttlw slew rate
|
||||
// @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second
|
||||
// @Units: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE", THROTTLE_SLEW_LIMIT),
|
||||
|
||||
// @Param: THR_FAILSAFE
|
||||
// @DisplayName: Throttle Failsafe Enable
|
||||
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE", THROTTLE_FAILSAFE),
|
||||
|
||||
// @Param: THR_FS_VALUE
|
||||
// @DisplayName: Throttle Failsafe Value
|
||||
// @Description: The PWM level on channel 3 below which throttle sailsafe triggers
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE", THROTTLE_FS_VALUE),
|
||||
|
||||
// @Param: TRIM_THROTTLE
|
||||
// @DisplayName: Throttle cruise percentage
|
||||
// @Description: The target percentage of throttle to apply for normal flight
|
||||
// @Units: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
|
||||
|
||||
// @Param: FS_SHORT_ACTN
|
||||
// @DisplayName: Short failsafe action
|
||||
// @Description: The action to take on a short (1 second) failsafe event
|
||||
// @Values: 0:None,1:ReturnToLaunch
|
||||
// @User: Standard
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN", SHORT_FAILSAFE_ACTION),
|
||||
|
||||
// @Param: FS_LONG_ACTN
|
||||
// @DisplayName: Long failsafe action
|
||||
// @Description: The action to take on a long (20 second) failsafe event
|
||||
// @Values: 0:None,1:ReturnToLaunch
|
||||
// @User: Standard
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN", LONG_FAILSAFE_ACTION),
|
||||
|
||||
// @Param: FS_GCS_ENABL
|
||||
// @DisplayName: GCS failsafe enable
|
||||
// @Description: Enable ground control station telemetry failsafe. Failsafe will trigger after 20 seconds of no MAVLink heartbeat messages
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_HEARTBEAT_FAILSAFE),
|
||||
|
||||
// @Param: FLTMODE_CH
|
||||
// @DisplayName: Flightmode channel
|
||||
// @Description: RC Channel to use for flight mode control
|
||||
// @User: Advanced
|
||||
GSCALAR(flight_mode_channel, "FLTMODE_CH", FLIGHT_MODE_CHANNEL),
|
||||
|
||||
// @Param: FLTMODE1
|
||||
// @DisplayName: FlightMode1
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)
|
||||
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
|
||||
|
||||
// @Param: FLTMODE2
|
||||
// @DisplayName: FlightMode2
|
||||
// @Description: Flight mode for switch position 2 (1231 to 1360)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
|
||||
|
||||
// @Param: FLTMODE3
|
||||
// @DisplayName: FlightMode3
|
||||
// @Description: Flight mode for switch position 3 (1361 to 1490)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
|
||||
|
||||
// @Param: FLTMODE4
|
||||
// @DisplayName: FlightMode4
|
||||
// @Description: Flight mode for switch position 4 (1491 to 1620)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
|
||||
|
||||
// @Param: FLTMODE5
|
||||
// @DisplayName: FlightMode5
|
||||
// @Description: Flight mode for switch position 5 (1621 to 1749)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
|
||||
|
||||
// @Param: FLTMODE6
|
||||
// @DisplayName: FlightMode6
|
||||
// @Description: Flight mode for switch position 6 (1750 to 2049)
|
||||
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||
|
||||
GSCALAR(roll_limit, "LIM_ROLL_CD", HEAD_MAX_CENTIDEGREE),
|
||||
|
|
Loading…
Reference in New Issue