mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
GCS_MAVLink: correct decimation of SENSOR_STATUS message
static infers shared between all backends
This commit is contained in:
parent
02e03f4b2e
commit
3101b08489
@ -850,6 +850,12 @@ private:
|
||||
|
||||
uint8_t last_battery_status_idx;
|
||||
|
||||
// send_sensor_offsets decimates its send rate using this counter:
|
||||
// FIXME: decimate this instead when initialising the message
|
||||
// intervals from the stream rates. Consider the implications of
|
||||
// doing so vis-a-vis the fact it will consume a bucket.
|
||||
uint8_t send_sensor_offsets_counter;
|
||||
|
||||
// if we've ever sent a DISTANCE_SENSOR message out of an
|
||||
// orientation we continue to send it out, even if it is not
|
||||
// longer valid.
|
||||
|
@ -1836,11 +1836,10 @@ void GCS_MAVLINK::send_sensor_offsets()
|
||||
|
||||
// run this message at a much lower rate - otherwise it
|
||||
// pointlessly wastes quite a lot of bandwidth
|
||||
static uint8_t counter;
|
||||
if (counter++ < 10) {
|
||||
if (send_sensor_offsets_counter++ < 10) {
|
||||
return;
|
||||
}
|
||||
counter = 0;
|
||||
send_sensor_offsets_counter = 0;
|
||||
|
||||
const Vector3f &mag_offsets = compass.get_offsets(0);
|
||||
const Vector3f &accel_offsets = ins.get_accel_offsets(0);
|
||||
|
Loading…
Reference in New Issue
Block a user