mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_Logger: added RATEMAX for mavlink and block backends
This commit is contained in:
parent
4dfe750d71
commit
d0969a4476
@ -116,13 +116,33 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
||||
AP_GROUPINFO("_FILE_MB_FREE", 7, AP_Logger, _params.min_MB_free, 500),
|
||||
|
||||
// @Param: _FILE_RATEMAX
|
||||
// @DisplayName: Maximum logging rate
|
||||
// @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
|
||||
// @Units: Hz
|
||||
// @Range: 0 1000
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_FILE_RATEMAX", 8, AP_Logger, _params.file_ratemax, 0),
|
||||
|
||||
#if HAL_LOGGING_MAVLINK_ENABLED
|
||||
// @Param: _MAV_RATEMAX
|
||||
// @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
|
||||
// @Units: Hz
|
||||
// @Range: 0 1000
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_MAV_RATEMAX", 9, AP_Logger, _params.mav_ratemax, 0),
|
||||
#endif
|
||||
|
||||
#if HAL_LOGGING_BLOCK_ENABLED
|
||||
// @Param: _BLK_RATEMAX
|
||||
// @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
|
||||
// @Units: Hz
|
||||
// @Range: 0 1000
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_BLK_RATEMAX", 10, AP_Logger, _params.blk_ratemax, 0),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -388,6 +388,8 @@ public:
|
||||
AP_Int16 file_timeout; // in seconds
|
||||
AP_Int16 min_MB_free;
|
||||
AP_Float file_ratemax;
|
||||
AP_Float mav_ratemax;
|
||||
AP_Float blk_ratemax;
|
||||
} _params;
|
||||
|
||||
const struct LogStructure *structure(uint16_t num) const;
|
||||
|
@ -303,6 +303,11 @@ void AP_Logger_Block::periodic_1Hz()
|
||||
{
|
||||
AP_Logger_Backend::periodic_1Hz();
|
||||
|
||||
if (rate_limiter == nullptr && _front._params.blk_ratemax > 0) {
|
||||
// setup rate limiting
|
||||
rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.blk_ratemax);
|
||||
}
|
||||
|
||||
if (!io_thread_alive()) {
|
||||
if (warning_decimation_counter == 0 && _initialised) {
|
||||
// we don't print this error unless we did initialise. When _initialised is set to true
|
||||
|
@ -524,6 +524,11 @@ void AP_Logger_MAVLink::periodic_10Hz(const uint32_t now)
|
||||
}
|
||||
void AP_Logger_MAVLink::periodic_1Hz()
|
||||
{
|
||||
if (rate_limiter == nullptr && _front._params.mav_ratemax > 0) {
|
||||
// setup rate limiting
|
||||
rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.mav_ratemax);
|
||||
}
|
||||
|
||||
if (_sending_to_client &&
|
||||
_last_response_time + 10000 < _last_send_time) {
|
||||
// other end appears to have timed out!
|
||||
|
Loading…
Reference in New Issue
Block a user