Browse Source

AP_Airspeed: add missing parameter metadata

mission-4.1.18
Peter Barker 9 years ago committed by Tom Pittenger
parent
commit
42f3f7195b
  1. 4
      libraries/AP_Airspeed/AP_Airspeed.cpp

4
libraries/AP_Airspeed/AP_Airspeed.cpp

@ -83,24 +83,28 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { @@ -83,24 +83,28 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @DisplayName: Airspeed enable
// @Description: enable airspeed sensor
// @Values: 0:Disable,1:Enable
// @User: Standard
AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Airspeed, _enable, 1, AP_PARAM_FLAG_ENABLE),
// @Param: USE
// @DisplayName: Airspeed use
// @Description: use airspeed for flight control
// @Values: 1:Use,0:Don't Use
// @User: Standard
AP_GROUPINFO("USE", 1, AP_Airspeed, _use, 0),
// @Param: OFFSET
// @DisplayName: Airspeed offset
// @Description: Airspeed calibration offset
// @Increment: 0.1
// @User: Advanced
AP_GROUPINFO("OFFSET", 2, AP_Airspeed, _offset, 0),
// @Param: RATIO
// @DisplayName: Airspeed ratio
// @Description: Airspeed calibration ratio
// @Increment: 0.1
// @User: Advanced
AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 1.9936f),
// @Param: PIN

Loading…
Cancel
Save