diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 33b57e5ee7..e58c91114a 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -273,7 +273,10 @@ void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, con sensor->get_mav_distance_sensor_type(), // type from MAV_DISTANCE_SENSOR enum 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 + 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings + 0, // horizontal FOV + 0, // vertical FOV + (const float *)nullptr); // quaternion of sensor orientation for MAV_SENSOR_ROTATION_CUSTOM } // send any and all distance_sensor messages. This starts by sending // any distance sensors not used by a Proximity sensor, then sends the @@ -357,7 +360,8 @@ void GCS_MAVLINK::send_proximity() const MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum PROXIMITY_SENSOR_ID_START + i, // onboard ID of the sensor dist_array.orientation[i], // direction the sensor faces from MAV_SENSOR_ORIENTATION enum - 0); // Measurement covariance in centimeters, 0 for unknown / invalid readings + 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings + 0, 0, nullptr); } } @@ -376,7 +380,8 @@ void GCS_MAVLINK::send_proximity() const MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum PROXIMITY_SENSOR_ID_START + PROXIMITY_MAX_DIRECTION + 1, // onboard ID of the sensor MAV_SENSOR_ROTATION_PITCH_90, // direction upwards - 0); // Measurement covariance in centimeters, 0 for unknown / invalid readings + 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings + 0, 0, nullptr); } }