mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_RPM: add missing parameter metadata
This commit is contained in:
parent
06b616f761
commit
ecd061dad5
@ -25,30 +25,35 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||||||
// @DisplayName: RPM type
|
// @DisplayName: RPM type
|
||||||
// @Description: What type of RPM sensor is connected
|
// @Description: What type of RPM sensor is connected
|
||||||
// @Values: 0:None,1:PX4-PWM
|
// @Values: 0:None,1:PX4-PWM
|
||||||
|
// @User: Standard
|
||||||
AP_GROUPINFO("_TYPE", 0, AP_RPM, _type[0], 0),
|
AP_GROUPINFO("_TYPE", 0, AP_RPM, _type[0], 0),
|
||||||
|
|
||||||
// @Param: _SCALING
|
// @Param: _SCALING
|
||||||
// @DisplayName: RPM scaling
|
// @DisplayName: RPM scaling
|
||||||
// @Description: Scaling factor between sensor reading and RPM.
|
// @Description: Scaling factor between sensor reading and RPM.
|
||||||
// @Increment: 0.001
|
// @Increment: 0.001
|
||||||
|
// @User: Standard
|
||||||
AP_GROUPINFO("_SCALING", 1, AP_RPM, _scaling[0], 1.0f),
|
AP_GROUPINFO("_SCALING", 1, AP_RPM, _scaling[0], 1.0f),
|
||||||
|
|
||||||
// @Param: _MAX
|
// @Param: _MAX
|
||||||
// @DisplayName: Maximum RPM
|
// @DisplayName: Maximum RPM
|
||||||
// @Description: Maximum RPM to report
|
// @Description: Maximum RPM to report
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @User: Standard
|
||||||
AP_GROUPINFO("_MAX", 2, AP_RPM, _maximum[0], 100000),
|
AP_GROUPINFO("_MAX", 2, AP_RPM, _maximum[0], 100000),
|
||||||
|
|
||||||
// @Param: _MIN
|
// @Param: _MIN
|
||||||
// @DisplayName: Minimum RPM
|
// @DisplayName: Minimum RPM
|
||||||
// @Description: Minimum RPM to report
|
// @Description: Minimum RPM to report
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @User: Standard
|
||||||
AP_GROUPINFO("_MIN", 3, AP_RPM, _minimum[0], 10),
|
AP_GROUPINFO("_MIN", 3, AP_RPM, _minimum[0], 10),
|
||||||
|
|
||||||
// @Param: _MIN_QUAL
|
// @Param: _MIN_QUAL
|
||||||
// @DisplayName: Minimum Quality
|
// @DisplayName: Minimum Quality
|
||||||
// @Description: Minimum data quality to be used
|
// @Description: Minimum data quality to be used
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("_MIN_QUAL", 4, AP_RPM, _quality_min[0], 0.5),
|
AP_GROUPINFO("_MIN_QUAL", 4, AP_RPM, _quality_min[0], 0.5),
|
||||||
|
|
||||||
#if RPM_MAX_INSTANCES > 1
|
#if RPM_MAX_INSTANCES > 1
|
||||||
@ -56,12 +61,14 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||||||
// @DisplayName: Second RPM type
|
// @DisplayName: Second RPM type
|
||||||
// @Description: What type of RPM sensor is connected
|
// @Description: What type of RPM sensor is connected
|
||||||
// @Values: 0:None,1:PX4-PWM
|
// @Values: 0:None,1:PX4-PWM
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("2_TYPE", 10, AP_RPM, _type[1], 0),
|
AP_GROUPINFO("2_TYPE", 10, AP_RPM, _type[1], 0),
|
||||||
|
|
||||||
// @Param: 2_SCALING
|
// @Param: 2_SCALING
|
||||||
// @DisplayName: RPM scaling
|
// @DisplayName: RPM scaling
|
||||||
// @Description: Scaling factor between sensor reading and RPM.
|
// @Description: Scaling factor between sensor reading and RPM.
|
||||||
// @Increment: 0.001
|
// @Increment: 0.001
|
||||||
|
// @User: Advanced
|
||||||
AP_GROUPINFO("2_SCALING", 11, AP_RPM, _scaling[1], 1.0f),
|
AP_GROUPINFO("2_SCALING", 11, AP_RPM, _scaling[1], 1.0f),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user