From 5dbcb8cd40d6222a3951173e8f8ea1e0e1a389a0 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 8 Aug 2024 14:58:43 +0200 Subject: [PATCH] camera_manager_plugin: bring back MAVLINK_COMM_1 channel I don't understand if and why it's necessary but found a way to do it with the struct encode method. --- src/gazebo_camera_manager_plugin.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/gazebo_camera_manager_plugin.cpp b/src/gazebo_camera_manager_plugin.cpp index 08e9a328b5..e35dbabb39 100644 --- a/src/gazebo_camera_manager_plugin.cpp +++ b/src/gazebo_camera_manager_plugin.cpp @@ -631,7 +631,7 @@ void CameraManagerPlugin::_handle_camera_info(const mavlink_message_t *pMsg, str | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;; mavlink_message_t msg; - mavlink_msg_camera_information_encode(_systemID, _componentID, &msg, &camera_information); + mavlink_msg_camera_information_encode_chan(_systemID, _componentID, MAVLINK_COMM_1, &msg, &camera_information); _send_mavlink_message(&msg, srcaddr); } @@ -723,7 +723,7 @@ void CameraManagerPlugin::_handle_request_video_stream_information(const mavlink video_stream_information.encoding = VIDEO_STREAM_ENCODING_H264; mavlink_message_t msg; - mavlink_msg_video_stream_information_encode(_systemID, _componentID, &msg, &video_stream_information); + mavlink_msg_video_stream_information_encode_chan(_systemID, _componentID, MAVLINK_COMM_1, &msg, &video_stream_information); _send_mavlink_message(&msg, srcaddr); }