mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: increase simulated rangefinder frequency to 5Hz
This commit is contained in:
parent
7b046c8b75
commit
c1acdc4994
@ -61,9 +61,9 @@ uint16_t SerialRangeFinder::calculate_range_cm(float range_value) const
|
|||||||
|
|
||||||
void SerialRangeFinder::update(float range)
|
void SerialRangeFinder::update(float range)
|
||||||
{
|
{
|
||||||
// just send a chunk of data at 1Hz:
|
// just send a chunk of data at 5Hz:
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (now - last_sent_ms < 1000) {
|
if (now - last_sent_ms < reading_interval_ms()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
last_sent_ms = now;
|
last_sent_ms = now;
|
||||||
|
@ -36,6 +36,8 @@ public:
|
|||||||
|
|
||||||
virtual uint32_t packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) = 0;
|
virtual uint32_t packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) = 0;
|
||||||
|
|
||||||
|
virtual uint16_t reading_interval_ms() const { return 200; } // 5Hz default
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
uint32_t last_sent_ms;
|
uint32_t last_sent_ms;
|
||||||
|
Loading…
Reference in New Issue
Block a user