mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Rangefinder: fixed param docs for Wasp backend
This commit is contained in:
parent
3b8d5ea4cf
commit
08228efc72
@ -21,39 +21,38 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_Param::GroupInfo AP_RangeFinder_Wasp::var_info[] = {
|
||||
|
||||
// @Param: WSP_MAVG
|
||||
// @DisplayName: Moving Average Range
|
||||
// @Description: Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
|
||||
// @Range 0-255
|
||||
// @Range: 0 255
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WSP_MAVG", 1, AP_RangeFinder_Wasp, mavg, 4),
|
||||
|
||||
// @Param: WSP_MEDF
|
||||
// @DisplayName: Moving Median Filter
|
||||
// @Description: Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
|
||||
// @Range 0-255
|
||||
// @Range: 0 255
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WSP_MEDF", 2, AP_RangeFinder_Wasp, medf, 4),
|
||||
|
||||
// @Param: WSP_FRQ
|
||||
// @DisplayName: Frequency
|
||||
// @Description: Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
|
||||
// @Range 0-10000
|
||||
// @Range: 0 10000
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WSP_FRQ", 3, AP_RangeFinder_Wasp, frq, 100),
|
||||
|
||||
// @Param: WSP_AVG
|
||||
// @DisplayName: Multi-pulse averages
|
||||
// @Description: Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
|
||||
// @Range 0-255
|
||||
// @Range: 0 255
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WSP_AVG", 4, AP_RangeFinder_Wasp, avg, 4),
|
||||
|
||||
// @Param: WSP_THR
|
||||
// @DisplayName: Sensitivity threshold
|
||||
// @Description: Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
|
||||
// @Range -1-255
|
||||
// @Range: -1 255
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WSP_THR", 5, AP_RangeFinder_Wasp, thr, -1),
|
||||
|
||||
|
@ -166,6 +166,8 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_ORIENT", 53, RangeFinder, state[0].orientation, ROTATION_PITCH_270),
|
||||
|
||||
// @Group: _
|
||||
// @Path: AP_RangeFinder_Wasp.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[0], "_", 57, RangeFinder, backend_var_info[0]),
|
||||
|
||||
#if RANGEFINDER_MAX_INSTANCES > 1
|
||||
@ -287,6 +289,8 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_ORIENT", 54, RangeFinder, state[1].orientation, ROTATION_PITCH_270),
|
||||
|
||||
// @Group: 2_
|
||||
// @Path: AP_RangeFinder_Wasp.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[1], "2_", 58, RangeFinder, backend_var_info[1]),
|
||||
#endif
|
||||
|
||||
@ -410,6 +414,8 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("3_ORIENT", 55, RangeFinder, state[2].orientation, ROTATION_PITCH_270),
|
||||
|
||||
// @Group: 3_
|
||||
// @Path: AP_RangeFinder_Wasp.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[2], "3_", 59, RangeFinder, backend_var_info[2]),
|
||||
#endif
|
||||
|
||||
@ -533,6 +539,8 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("4_ORIENT", 56, RangeFinder, state[3].orientation, ROTATION_PITCH_270),
|
||||
|
||||
// @Group: 4_
|
||||
// @Path: AP_RangeFinder_Wasp.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[3], "4_", 60, RangeFinder, backend_var_info[3]),
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user