GCS_MAVLink: adapt to new rangefinder method name

This commit is contained in:
Peter Barker 2017-08-08 17:25:09 +10:00 committed by Francisco Ferreira
parent 30c4ea8123
commit b6076bcb77
1 changed files with 8 additions and 8 deletions

View File

@ -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