From 5c15c2efc37773c4d5fedb7dca5afe34fc725b19 Mon Sep 17 00:00:00 2001 From: Pedro Roque Date: Mon, 13 May 2024 16:04:14 +0200 Subject: [PATCH] fix: revert mavlink changes, now compiles with upstream --- src/gazebo_camera_manager_plugin.cpp | 3 ++- src/gazebo_gimbal_controller_plugin.cpp | 6 ++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/gazebo_camera_manager_plugin.cpp b/src/gazebo_camera_manager_plugin.cpp index 943a887fc2..17fcdf051a 100644 --- a/src/gazebo_camera_manager_plugin.cpp +++ b/src/gazebo_camera_manager_plugin.cpp @@ -639,7 +639,8 @@ void CameraManagerPlugin::_handle_camera_info(const mavlink_message_t *pMsg, str 0, // lens_id camera_capabilities, // CAP_FLAGS 0, // Camera Definition Version - uri // URI + uri, // URI, + 0 ); _send_mavlink_message(&msg, srcaddr); } diff --git a/src/gazebo_gimbal_controller_plugin.cpp b/src/gazebo_gimbal_controller_plugin.cpp index 900ca586a4..3099820db4 100644 --- a/src/gazebo_gimbal_controller_plugin.cpp +++ b/src/gazebo_gimbal_controller_plugin.cpp @@ -682,7 +682,8 @@ void GimbalControllerPlugin::SendGimbalDeviceInformation() pitchMin, pitchMax, yawMin, - yawMax); + yawMax, + 0); SendMavlinkMessage(msg); } @@ -736,7 +737,8 @@ void GimbalControllerPlugin::SendGimbalDeviceAttitudeStatus() angularVelocity.Z(), failureFlags, NAN, // per mavlink spec - NAN if unknown - NAN); + NAN, + 0); SendMavlinkMessage(msg); }