From b6076bcb77d376b88a8a881d7e6b01ffe9a8c7c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 8 Aug 2017 17:25:09 +1000 Subject: [PATCH] GCS_MAVLink: adapt to new rangefinder method name --- libraries/GCS_MAVLink/GCS_Common.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0af3682d20..3e1d7ac698 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -227,14 +227,14 @@ void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor) con mavlink_msg_distance_sensor_send( chan, - AP_HAL::millis(), // time since system boot TODO: take time of measurement - sensor->min_distance_cm(), // minimum distance the sensor can measure in centimeters - sensor->max_distance_cm(), // maximum distance the sensor can measure in centimeters - sensor->distance_cm(), // current distance reading - sensor->get_sensor_type(), // type from MAV_DISTANCE_SENSOR enum - sensor->instance(), // onboard ID of the sensor == instance - sensor->orientation(), // direction the sensor faces from MAV_SENSOR_ORIENTATION enum - 0); // Measurement covariance in centimeters, 0 for unknown / invalid readings + AP_HAL::millis(), // time since system boot TODO: take time of measurement + sensor->min_distance_cm(), // minimum distance the sensor can measure in centimeters + sensor->max_distance_cm(), // maximum distance the sensor can measure in centimeters + sensor->distance_cm(), // current distance reading + sensor->get_mav_distance_sensor_type(), // type from MAV_DISTANCE_SENSOR enum + sensor->instance(), // onboard ID of the sensor == instance + sensor->orientation(), // direction the sensor faces from MAV_SENSOR_ORIENTATION enum + 0); // Measurement covariance in centimeters, 0 for unknown / invalid readings } bool GCS_MAVLINK::send_distance_sensor(const RangeFinder &rangefinder) const