mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Airspeed Library - fix param names.
The Group definition give the start of the param name. This way we can maintain multiple instances if required of the same library as options.
This commit is contained in:
parent
822e682140
commit
9e4d118fdb
@ -16,25 +16,25 @@
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = {
|
||||
|
||||
// @Param: ARSPD_ENABLE
|
||||
// @Param: ENABLE
|
||||
// @DisplayName: Airspeed enable
|
||||
// @Description: enable airspeed sensor
|
||||
// @Values: 0:Disable,1:Enable
|
||||
AP_GROUPINFO("ENABLE", 0, AP_Airspeed, _enable),
|
||||
|
||||
// @Param: ARSPD_USE
|
||||
// @Param: USE
|
||||
// @DisplayName: Airspeed use
|
||||
// @Description: use airspeed for flight control
|
||||
// @Values: 0:Use,1:Don't Use
|
||||
AP_GROUPINFO("USE", 1, AP_Airspeed, _use),
|
||||
|
||||
// @Param: ARSPD_OFFSET
|
||||
// @Param: OFFSET
|
||||
// @DisplayName: Airspeed offset
|
||||
// @Description: Airspeed calibration offset
|
||||
// @Increment: 0.1
|
||||
AP_GROUPINFO("OFFSET", 2, AP_Airspeed, _offset),
|
||||
|
||||
// @Param: ARSPD_RATIO
|
||||
// @Param: RATIO
|
||||
// @DisplayName: Airspeed ratio
|
||||
// @Description: Airspeed calibration ratio
|
||||
// @Increment: 0.1
|
||||
|
Loading…
Reference in New Issue
Block a user