mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Logger: fix _RATEMAX parameter descriptions
This commit is contained in:
parent
21b7a8b682
commit
5f7f1cff2b
@ -118,7 +118,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
|||||||
|
|
||||||
// @Param: _FILE_RATEMAX
|
// @Param: _FILE_RATEMAX
|
||||||
// @DisplayName: Maximum logging rate for file backend
|
// @DisplayName: Maximum logging rate for file backend
|
||||||
// @Description: This sets the maximum rate that streaming log messages will be logged to the file backend. A value of zero means
|
// @Description: This sets the maximum rate that streaming log messages will be logged to the file backend. A value of zero means that rate limiting is disabled.
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 1000
|
// @Range: 0 1000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
@ -127,7 +127,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
|||||||
#if HAL_LOGGING_MAVLINK_ENABLED
|
#if HAL_LOGGING_MAVLINK_ENABLED
|
||||||
// @Param: _MAV_RATEMAX
|
// @Param: _MAV_RATEMAX
|
||||||
// @DisplayName: Maximum logging rate for mavlink backend
|
// @DisplayName: Maximum logging rate for mavlink backend
|
||||||
// @Description: This sets the maximum rate that streaming log messages will be logged to the mavlink backend. A value of zero means
|
// @Description: This sets the maximum rate that streaming log messages will be logged to the mavlink backend. A value of zero means that rate limiting is disabled.
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 1000
|
// @Range: 0 1000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
@ -137,7 +137,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
|||||||
#if HAL_LOGGING_BLOCK_ENABLED
|
#if HAL_LOGGING_BLOCK_ENABLED
|
||||||
// @Param: _BLK_RATEMAX
|
// @Param: _BLK_RATEMAX
|
||||||
// @DisplayName: Maximum logging rate for block backend
|
// @DisplayName: Maximum logging rate for block backend
|
||||||
// @Description: This sets the maximum rate that streaming log messages will be logged to the mavlink backend. A value of zero means
|
// @Description: This sets the maximum rate that streaming log messages will be logged to the mavlink backend. A value of zero means that rate limiting is disabled.
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 1000
|
// @Range: 0 1000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
Loading…
Reference in New Issue
Block a user