mavlink: DISTANCE_SENSOR: propagate signal_quality metric

This commit is contained in:
TSC21
2020-06-20 17:03:34 +01:00
committed by Nuno Marques
parent d34b5f86cc
commit b3bbc351ca
3 changed files with 11 additions and 3 deletions
+5 -1
View File
@@ -1144,7 +1144,11 @@ int Simulator::publish_distance_topic(const mavlink_distance_sensor_t *dist_mavl
dist.type = dist_mavlink->type;
dist.id = dist_mavlink->id;
dist.variance = dist_mavlink->covariance * 1e-4f; // cm^2 to m^2
dist.signal_quality = -1;
// MAVLink DISTANCE_SENSOR signal_quality value of 0 means unset/unknown
// quality value. Also it comes normalised between 1 and 100 while the uORB
// signal quality is normalised between 0 and 100.
dist.signal_quality = dist_mavlink->signal_quality == 0 ? -1 : 100 * (dist_mavlink->signal_quality - 1) / 99;
switch (dist_mavlink->orientation) {
case MAV_SENSOR_ORIENTATION::MAV_SENSOR_ROTATION_PITCH_270: