mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: add AUX switch to pause logging of streamed entries
This commit is contained in:
parent
f9f0f60815
commit
a395b3d2a8
|
@ -250,6 +250,12 @@ public:
|
|||
void set_num_types(uint8_t num_types) { _num_types = num_types; }
|
||||
|
||||
bool CardInserted(void);
|
||||
bool _log_pause;
|
||||
|
||||
// pause logging if aux switch is active and log rate limit enabled
|
||||
void log_pause(bool value) {
|
||||
_log_pause = value;
|
||||
}
|
||||
|
||||
// erase handling
|
||||
void EraseAll();
|
||||
|
|
|
@ -658,9 +658,8 @@ AP_Logger_RateLimiter::AP_Logger_RateLimiter(const AP_Logger &_front, const AP_F
|
|||
*/
|
||||
bool AP_Logger_RateLimiter::should_log_streaming(uint8_t msgid)
|
||||
{
|
||||
if (rate_limit_hz <= 0) {
|
||||
// no limiting (user changed the parameter)
|
||||
return true;
|
||||
if (front._log_pause) {
|
||||
return false;
|
||||
}
|
||||
const uint16_t now = AP_HAL::millis16();
|
||||
uint16_t delta_ms = now - last_send_ms[msgid];
|
||||
|
@ -678,8 +677,8 @@ bool AP_Logger_RateLimiter::should_log_streaming(uint8_t msgid)
|
|||
*/
|
||||
bool AP_Logger_RateLimiter::should_log(uint8_t msgid, bool writev_streaming)
|
||||
{
|
||||
if (rate_limit_hz <= 0) {
|
||||
// no limiting (user changed the parameter)
|
||||
if (rate_limit_hz <= 0 && !front._log_pause) {
|
||||
// no rate limiting if not paused and rate is zero(user changed the parameter)
|
||||
return true;
|
||||
}
|
||||
if (last_send_ms[msgid] == 0 && !writev_streaming) {
|
||||
|
|
|
@ -307,8 +307,8 @@ void AP_Logger_Block::periodic_1Hz()
|
|||
{
|
||||
AP_Logger_Backend::periodic_1Hz();
|
||||
|
||||
if (rate_limiter == nullptr && _front._params.blk_ratemax > 0) {
|
||||
// setup rate limiting
|
||||
if (rate_limiter == nullptr && (_front._params.blk_ratemax > 0 || _front._log_pause)) {
|
||||
// setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested
|
||||
rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.blk_ratemax);
|
||||
}
|
||||
|
||||
|
|
|
@ -153,8 +153,8 @@ void AP_Logger_File::periodic_1Hz()
|
|||
}
|
||||
}
|
||||
|
||||
if (rate_limiter == nullptr && _front._params.file_ratemax > 0) {
|
||||
// setup rate limiting
|
||||
if (rate_limiter == nullptr && (_front._params.file_ratemax > 0 || _front._log_pause)) {
|
||||
// setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested
|
||||
rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.file_ratemax);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -524,8 +524,8 @@ 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
|
||||
if (rate_limiter == nullptr && (_front._params.mav_ratemax > 0 || _front._log_pause)) {
|
||||
// setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested
|
||||
rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.mav_ratemax);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue