mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 04:33:10 +08:00
sensors: relax default data_validator timeout 20->40ms
This commit is contained in:
@@ -166,7 +166,7 @@ public:
|
||||
private:
|
||||
uint32_t _error_mask{ERROR_FLAG_NO_ERROR}; /**< sensor error state */
|
||||
|
||||
uint32_t _timeout_interval{20000}; /**< interval in which the datastream times out in us */
|
||||
uint32_t _timeout_interval{40000}; /**< interval in which the datastream times out in us */
|
||||
|
||||
uint64_t _time_last{0}; /**< last timestamp */
|
||||
uint64_t _event_count{0}; /**< total data counter */
|
||||
|
||||
Reference in New Issue
Block a user