mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Airspeed: correct metadata in libraries failing checks on emitter
This commit is contained in:
parent
eb3f80da7c
commit
db496cf256
@ -109,7 +109,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
// @Param: _USE
|
||||
// @DisplayName: Airspeed use
|
||||
// @Description{Plane}: Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).
|
||||
// @Description: Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).
|
||||
// @Description{Copter, Blimp, Rover, Sub}: This parameter is not used by this vehicle. Always set to 0.
|
||||
// @Values: 0:DoNotUse,1:Use,2:UseWhenZeroThrottle
|
||||
// @User: Standard
|
||||
@ -188,7 +188,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
// @Param: _OPTIONS
|
||||
// @DisplayName: Airspeed options bitmask
|
||||
// @Description{Plane}: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction
|
||||
// @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction
|
||||
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
|
||||
// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection
|
||||
// @User: Advanced
|
||||
@ -221,7 +221,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
||||
|
||||
// @Param: 2_USE
|
||||
// @DisplayName: Enable use of 2nd airspeed sensor
|
||||
// @Description{Plane}: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
|
||||
// @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller
|
||||
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
|
||||
// @Values: 0:Don't Use,1:use,2:UseWhenZeroThrottle
|
||||
// @User: Standard
|
||||
@ -249,7 +249,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
||||
|
||||
// @Param: 2_AUTOCAL
|
||||
// @DisplayName: Automatic airspeed ratio calibration for 2nd airspeed sensor
|
||||
// @Description{Plane}: If this is enabled then the autopilot will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
|
||||
// @Description: If this is enabled then the autopilot will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended.
|
||||
// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_AUTOCAL", 16, AP_Airspeed, param[1].autocal, 0),
|
||||
|
Loading…
Reference in New Issue
Block a user