mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: added note on type of airspeed in docs
This commit is contained in:
parent
01c124d5f5
commit
53b1b9b575
@ -250,7 +250,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
// @Param: ARSPD_FBW_MIN
|
||||
// @DisplayName: Fly By Wire Minimum Airspeed
|
||||
// @Description: Airspeed corresponding to minimum throttle in auto throttle modes (FBWB, CRUISE, AUTO, GUIDED, LOITER, CIRCLE and RTL)
|
||||
// @Description: Airspeed corresponding to minimum throttle in auto throttle modes (FBWB, CRUISE, AUTO, GUIDED, LOITER, CIRCLE and RTL). This is a calibrated (apparent) airspeed.
|
||||
// @Units: m/s
|
||||
// @Range: 5 50
|
||||
// @Increment: 1
|
||||
@ -259,7 +259,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
// @Param: ARSPD_FBW_MAX
|
||||
// @DisplayName: Fly By Wire Maximum Airspeed
|
||||
// @Description: Airspeed corresponding to maximum throttle in auto throttle modes (FBWB, CRUISE, AUTO, GUIDED, LOITER, CIRCLE and RTL)
|
||||
// @Description: Airspeed corresponding to maximum throttle in auto throttle modes (FBWB, CRUISE, AUTO, GUIDED, LOITER, CIRCLE and RTL). This is a calibrated (apparent) airspeed.
|
||||
// @Units: m/s
|
||||
// @Range: 5 50
|
||||
// @Increment: 1
|
||||
@ -585,7 +585,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
// @Param: TRIM_ARSPD_CM
|
||||
// @DisplayName: Target airspeed
|
||||
// @Description: Airspeed in cm/s to aim for when airspeed is enabled in auto mode
|
||||
// @Description: Airspeed in cm/s to aim for when airspeed is enabled in auto mode. This is a calibrated (apparent) airspeed.
|
||||
// @Units: cm/s
|
||||
// @User: User
|
||||
GSCALAR(airspeed_cruise_cm, "TRIM_ARSPD_CM", AIRSPEED_CRUISE_CM),
|
||||
|
Loading…
Reference in New Issue
Block a user