Skip to content

Commit

Permalink
camera_manager: mavlink update
Browse files Browse the repository at this point in the history
The update requires to set the camera_device_id in this case signalling
that it is a MAVLink camera with its own MAVLink component ID.
  • Loading branch information
julianoes committed Oct 10, 2024
1 parent f1d11a6 commit eb03f87
Showing 1 changed file with 9 additions and 6 deletions.
15 changes: 9 additions & 6 deletions src/gazebo_camera_manager_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -657,7 +657,8 @@ void CameraManagerPlugin::_handle_request_camera_settings(const mavlink_message_
0, // time_boot_ms
_mode, // Camera Mode
1.0E2 * (_zoom - 1.0)/ (_maxZoom - 1.0), // Zoom level
NAN); // Focus level
NAN, // Focus level
0); // MAVLink camera with its own component ID
_send_mavlink_message(&msg, srcaddr);
}

Expand All @@ -678,18 +679,19 @@ void CameraManagerPlugin::_handle_request_video_stream_status(const mavlink_mess
mavlink_message_t msg;
mavlink_msg_video_stream_status_pack_chan(
_systemID,
_componentID, // Component ID
_componentID, // Component ID
MAVLINK_COMM_1,
&msg,
static_cast<uint8_t>(sid), // Stream ID
VIDEO_STREAM_STATUS_FLAGS_RUNNING, // Flags (It's always running)
30, // Frame rate
_width, // Horizontal resolution
_width, // Horizontal resolution
_height, // Vertical resolution
2048, // Bit rate (made up)
0, // Rotation (none)
90 // FOV (made up)
);
90, // FOV (made up)
0); // MAVLink camera with its own component ID

_send_mavlink_message(&msg, srcaddr);
}

Expand Down Expand Up @@ -801,7 +803,8 @@ void CameraManagerPlugin::_send_capture_status(struct sockaddr* srcaddr)
interval, // image interval
recording_time_ms, // recording time in ms
available_mib, // available storage capacity
_imageCounter); // total number of images
_imageCounter, // total number of images
0); // MAVLink camera with its own component ID
_send_mavlink_message(&msg, srcaddr);
}

Expand Down

0 comments on commit eb03f87

Please sign in to comment.