Skip to content

Commit

Permalink
camera_manager_plugin: fix mavlink messages for camera info and video…
Browse files Browse the repository at this point in the history
… stream information

This time with structs instead of the direct pack_chan() calls that might break again quickly.
  • Loading branch information
MaEtUgR committed Aug 7, 2024
1 parent 67af3c3 commit 5fb9e78
Showing 1 changed file with 37 additions and 46 deletions.
83 changes: 37 additions & 46 deletions src/gazebo_camera_manager_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -614,34 +614,30 @@ void CameraManagerPlugin::_handle_camera_info(const mavlink_message_t *pMsg, str
{
gzdbg << "Send camera info" << endl;
_send_cmd_ack(pMsg->sysid, pMsg->compid, MAV_CMD_REQUEST_CAMERA_INFORMATION, MAV_RESULT_ACCEPTED, srcaddr);
static const char vendor[MAVLINK_MSG_CAMERA_INFORMATION_FIELD_VENDOR_NAME_LEN] = "PX4.io";
static const char model[MAVLINK_MSG_CAMERA_INFORMATION_FIELD_MODEL_NAME_LEN] = "Gazebo";
static const char uri[MAVLINK_MSG_CAMERA_INFORMATION_FIELD_CAM_DEFINITION_URI_LEN] = {};
uint32_t camera_capabilities = CAMERA_CAP_FLAGS_CAPTURE_IMAGE | CAMERA_CAP_FLAGS_CAPTURE_VIDEO |
CAMERA_CAP_FLAGS_HAS_MODES | CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM |
CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;

mavlink_camera_information_t camera_information{};
camera_information.time_boot_ms = 0;
std::strcpy((char *)camera_information.vendor_name, "PX4.io");
std::strcpy((char *)camera_information.model_name, "Gazebo");
camera_information.firmware_version = 0x01;
camera_information.focal_length = 50.f;
camera_information.sensor_size_h = 35.f;
camera_information.sensor_size_v = 24.f;
camera_information.resolution_h = _width;
camera_information.resolution_v = _height;
camera_information.lens_id = 0;
camera_information.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE
| CAMERA_CAP_FLAGS_CAPTURE_VIDEO
| CAMERA_CAP_FLAGS_HAS_MODES
| CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM
| CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM;;
camera_information.cam_definition_version = 0;
std::strcpy(camera_information.cam_definition_uri, "");
camera_information.gimbal_device_id = 0;
camera_information.camera_device_id = 0;

mavlink_message_t msg;
mavlink_msg_camera_information_pack_chan(
_systemID,
_componentID,
MAVLINK_COMM_1,
&msg,
0, // time_boot_ms
(const uint8_t *)vendor, // const uint8_t * vendor_name
(const uint8_t *)model, // const uint8_t * model_name
0x01, // uint32_t firmware_version
50.0f, // float focal_lenth
35.0f, // float sensor_size_h
24.0f, // float sensor_size_v
_width, // resolution_h
_height, // resolution_v
0, // lens_id
camera_capabilities, // CAP_FLAGS
0, // Camera Definition Version
uri, // URI
0 // uint8_t gimbal_device_id
);
mavlink_msg_camera_information_encode(_systemID, _componentID, &msg, &camera_information);
_send_mavlink_message(&msg, srcaddr);
}

Expand Down Expand Up @@ -706,8 +702,6 @@ void CameraManagerPlugin::_handle_request_video_stream_status(const mavlink_mess
void CameraManagerPlugin::_handle_request_video_stream_information(const mavlink_message_t *pMsg, struct sockaddr* srcaddr)
{
gzdbg << "Send videostream information" << endl;
char name[MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_NAME_LEN] = {};
snprintf(name, MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_NAME_LEN, "Visual Spectrum");
mavlink_command_long_t cmd;
mavlink_msg_command_long_decode(pMsg, &cmd);
//-- Should we execute the command
Expand All @@ -720,25 +714,22 @@ void CameraManagerPlugin::_handle_request_video_stream_information(const mavlink
// ACK command received and accepted
_send_cmd_ack(pMsg->sysid, pMsg->compid, MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, MAV_RESULT_ACCEPTED, srcaddr);

mavlink_video_stream_information_t video_stream_information{};
video_stream_information.stream_id = 1;
video_stream_information.count = 1;
video_stream_information.type = VIDEO_STREAM_TYPE_RTPUDP;
video_stream_information.flags = VIDEO_STREAM_STATUS_FLAGS_RUNNING; // It's always running
video_stream_information.framerate = 30;
video_stream_information.resolution_h = _width;
video_stream_information.resolution_v = _height;
video_stream_information.bitrate = 2048;
video_stream_information.rotation = 0; // none
video_stream_information.hfov = 90; // made up
std::strcpy(video_stream_information.name, "Visual Spectrum");
std::strcpy(video_stream_information.uri, _videoURI.c_str());

mavlink_message_t msg;
mavlink_msg_video_stream_information_pack_chan(
_systemID,
_componentID, // Component ID
MAVLINK_COMM_1,
&msg,
1, // Stream ID
1, // Stream count
VIDEO_STREAM_TYPE_RTPUDP, // Stream type
VIDEO_STREAM_STATUS_FLAGS_RUNNING, // Flags (It's always running)
30, // Frame rate
_width, // Horizontal resolution
_height, // Vertical resolution
2048, // Bit rate
0, // Rotation (none)
90, // FOV (made up)
name,
_videoURI.c_str()
);
mavlink_msg_video_stream_information_encode(_systemID, _componentID, &msg, &video_stream_information);
_send_mavlink_message(&msg, srcaddr);
}

Expand Down

0 comments on commit 5fb9e78

Please sign in to comment.