From 84b0f6478c7d7d08fa65e338e390e2a8b1b431c0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Fran=C3=A7ois=20Carouge?= Date: Thu, 30 Jun 2022 21:46:01 -0700 Subject: [PATCH] SITL/SIM_RF_MAVLink: fix incomplete initializer clauses --- libraries/SITL/SIM_RF_MAVLink.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/SITL/SIM_RF_MAVLink.cpp b/libraries/SITL/SIM_RF_MAVLink.cpp index 1434217d63..e075fa4d9d 100644 --- a/libraries/SITL/SIM_RF_MAVLink.cpp +++ b/libraries/SITL/SIM_RF_MAVLink.cpp @@ -40,17 +40,17 @@ uint32_t RF_MAVLink::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t bu const uint8_t system_id = 32; const uint8_t component_id = 32; const mavlink_distance_sensor_t distance_sensor{ - time_boot_ms: AP_HAL::millis(), - min_distance: 10, // cm - max_distance: 1000, // cm - current_distance: alt_cm, - type: 0, - id: 72, // ID - MAV_SENSOR_ROTATION_PITCH_270, - 255, // 255 is unknown covariance - 0, // 0 is unknown horizontal fov - 0, // 0 is unknown vertical fov - {0,0,0,0} // unknown/unused quat + .time_boot_ms = AP_HAL::millis(), + .min_distance = 10, // cm + .max_distance = 1000, // cm + .current_distance = alt_cm, + .type = 0, + .id = 72, // ID + .orientation = MAV_SENSOR_ROTATION_PITCH_270, + .covariance = 255, // 255 is unknown covariance + .horizontal_fov = 0, // 0 is unknown horizontal fov + .vertical_fov = 0, // 0 is unknown vertical fov + .quaternion = {0,0,0,0} // unknown/unused quat }; const uint16_t len = mavlink_msg_distance_sensor_encode(system_id, component_id,