mavlink: Only send the distance sensor message if the topic actually updates

This commit is contained in:
Lorenz Meier 2014-05-06 12:55:39 +02:00
parent 5bc7295145
commit df6a0d5a1a
1 changed files with 14 additions and 13 deletions

View File

@ -1339,7 +1339,7 @@ protected:
void send(const hrt_abstime t) void send(const hrt_abstime t)
{ {
(void)range_sub->update(t); if (range_sub->update(t)) {
uint8_t type; uint8_t type;
@ -1356,6 +1356,7 @@ protected:
mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation, mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance); range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
} }
}
}; };
MavlinkStream *streams_list[] = { MavlinkStream *streams_list[] = {