Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add more video streaming info #2231

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 10 additions & 3 deletions examples/camera_server/camera_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,22 @@ int main(int argc, char** argv)
auto ret = camera_server.set_information({
.vendor_name = "MAVSDK",
.model_name = "Example Camera Server",
.firmware_version = "1.0.0",
.firmware_version = "0.1.0.12",
.focal_length_mm = 3.0,
.horizontal_sensor_size_mm = 3.68,
.vertical_sensor_size_mm = 2.76,
.horizontal_resolution_px = 3280,
.vertical_resolution_px = 2464,
.lens_id = 0,
.definition_file_version = 0, // TODO: add this
.definition_file_uri = "", // TODO: implement this using MAVLink FTP
.definition_file_version = 1,
.definition_file_uri = "http://192.168.0.1/demo.xml",
.camera_cap_flags =
{
mavsdk::CameraServer::Information::CameraCapFlags::CaptureImage,
mavsdk::CameraServer::Information::CameraCapFlags::CaptureVideo,
mavsdk::CameraServer::Information::CameraCapFlags::HasModes,
mavsdk::CameraServer::Information::CameraCapFlags::HasVideoStream,
},
});

// set video stream info
Expand Down
49 changes: 48 additions & 1 deletion src/mavsdk/plugins/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -579,9 +579,42 @@ std::ostream& operator<<(std::ostream& str, Camera::SettingOptions const& settin
return str;
}

std::ostream&
operator<<(std::ostream& str, Camera::Information::CameraCapFlags const& camera_cap_flags)
{
switch (camera_cap_flags) {
case Camera::Information::CameraCapFlags::CaptureVideo:
return str << "Capture Video";
case Camera::Information::CameraCapFlags::CaptureImage:
return str << "Capture Image";
case Camera::Information::CameraCapFlags::HasModes:
return str << "Has Modes";
case Camera::Information::CameraCapFlags::CanCaptureImageInVideoMode:
return str << "Can Capture Image In Video Mode";
case Camera::Information::CameraCapFlags::CanCaptureVideoInImageMode:
return str << "Can Capture Video In Image Mode";
case Camera::Information::CameraCapFlags::HasImageSurveyMode:
return str << "Has Image Survey Mode";
case Camera::Information::CameraCapFlags::HasBasicZoom:
return str << "Has Basic Zoom";
case Camera::Information::CameraCapFlags::HasBasicFocus:
return str << "Has Basic Focus";
case Camera::Information::CameraCapFlags::HasVideoStream:
return str << "Has Video Stream";
case Camera::Information::CameraCapFlags::HasTrackingPoint:
return str << "Has Tracking Point";
case Camera::Information::CameraCapFlags::HasTrackingRectangle:
return str << "Has Tracking Rectangle";
case Camera::Information::CameraCapFlags::HasTrackingGeoStatus:
return str << "Has Tracking Geo Status";
default:
return str << "Unknown";
}
}
bool operator==(const Camera::Information& lhs, const Camera::Information& rhs)
{
return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) &&
(rhs.firmware_version == lhs.firmware_version) &&
((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) ||
rhs.focal_length_mm == lhs.focal_length_mm) &&
((std::isnan(rhs.horizontal_sensor_size_mm) &&
Expand All @@ -590,7 +623,11 @@ bool operator==(const Camera::Information& lhs, const Camera::Information& rhs)
((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) ||
rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) &&
(rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) &&
(rhs.vertical_resolution_px == lhs.vertical_resolution_px);
(rhs.vertical_resolution_px == lhs.vertical_resolution_px) &&
(rhs.lens_id == lhs.lens_id) &&
(rhs.definition_file_version == lhs.definition_file_version) &&
(rhs.definition_file_uri == lhs.definition_file_uri) &&
(rhs.camera_cap_flags == lhs.camera_cap_flags);
}

std::ostream& operator<<(std::ostream& str, Camera::Information const& information)
Expand All @@ -599,11 +636,21 @@ std::ostream& operator<<(std::ostream& str, Camera::Information const& informati
str << "information:" << '\n' << "{\n";
str << " vendor_name: " << information.vendor_name << '\n';
str << " model_name: " << information.model_name << '\n';
str << " firmware_version: " << information.firmware_version << '\n';
str << " focal_length_mm: " << information.focal_length_mm << '\n';
str << " horizontal_sensor_size_mm: " << information.horizontal_sensor_size_mm << '\n';
str << " vertical_sensor_size_mm: " << information.vertical_sensor_size_mm << '\n';
str << " horizontal_resolution_px: " << information.horizontal_resolution_px << '\n';
str << " vertical_resolution_px: " << information.vertical_resolution_px << '\n';
str << " lens_id: " << information.lens_id << '\n';
str << " definition_file_version: " << information.definition_file_version << '\n';
str << " definition_file_uri: " << information.definition_file_uri << '\n';
str << " camera_cap_flags: [";
for (auto it = information.camera_cap_flags.begin(); it != information.camera_cap_flags.end();
++it) {
str << *it;
str << (it + 1 != information.camera_cap_flags.end() ? ", " : "]\n");
}
str << '}';
return str;
}
Expand Down
68 changes: 68 additions & 0 deletions src/mavsdk/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1166,11 +1166,69 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message)

_information.data.vendor_name = (char*)(camera_information.vendor_name);
_information.data.model_name = (char*)(camera_information.model_name);
parse_version_int(_information.data.firmware_version, camera_information.firmware_version);
_information.data.focal_length_mm = camera_information.focal_length;
_information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h;
_information.data.vertical_sensor_size_mm = camera_information.sensor_size_v;
_information.data.horizontal_resolution_px = camera_information.resolution_h;
_information.data.vertical_resolution_px = camera_information.resolution_v;
_information.data.lens_id = camera_information.lens_id;
_information.data.definition_file_version = camera_information.cam_definition_version;
_information.data.definition_file_uri = camera_information.cam_definition_uri;

// TODO : may need optimize code
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::CaptureVideo);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::CaptureImage);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES) != 0) {
_information.data.camera_cap_flags.push_back(Camera::Information::CameraCapFlags::HasModes);
}
if ((camera_information.flags &
CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::CanCaptureImageInVideoMode);
}
if ((camera_information.flags &
CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::CanCaptureVideoInImageMode);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE) !=
0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasImageSurveyMode);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasBasicZoom);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasBasicFocus);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasVideoStream);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_POINT) != 0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasTrackingPoint);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE) !=
0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasTrackingRectangle);
}
if ((camera_information.flags & CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS) !=
0) {
_information.data.camera_cap_flags.push_back(
Camera::Information::CameraCapFlags::HasTrackingGeoStatus);
}

_information.subscription_callbacks.queue(
_information.data, [this](const auto& func) { _system_impl->call_user_callback(func); });
Expand Down Expand Up @@ -2156,4 +2214,14 @@ void CameraImpl::list_photos_async(
}).detach();
}

bool CameraImpl::parse_version_int(std::string& version_str, uint32_t version_int)
{
//(Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)
std::stringstream ss;
ss << (version_int & 0xff) << "." << (version_int >> 8 & 0xff) << "."
<< (version_int >> 16 & 0xff) << "." << (version_int >> 24 & 0xff);
version_str = ss.str();
return true;
}

} // namespace mavsdk
2 changes: 2 additions & 0 deletions src/mavsdk/plugins/camera/camera_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,8 @@ class CameraImpl : public PluginImplBase {

void request_missing_capture_info();

bool parse_version_int(std::string& version_str, uint32_t version_int);

std::unique_ptr<CameraDefinition> _camera_definition{};
bool _is_fetching_camera_definition{false};
bool _has_camera_definition_timed_out{false};
Expand Down
44 changes: 44 additions & 0 deletions src/mavsdk/plugins/camera/include/plugins/camera/camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -469,13 +469,57 @@ class Camera : public PluginBase {
* @brief Type to represent a camera information.
*/
struct Information {
/**
* @brief
*/
enum class CameraCapFlags {
CaptureVideo, /**< @brief Camera is able to record video. */
CaptureImage, /**< @brief Camera is able to capture images. */
HasModes, /**< @brief Camera has separate Video and Image/Photo modes
(MAV_CMD_SET_CAMERA_MODE). */
CanCaptureImageInVideoMode, /**< @brief Camera can capture images while in video mode.
*/
CanCaptureVideoInImageMode, /**< @brief Camera can capture videos while in Photo/Image
mode. */
HasImageSurveyMode, /**< @brief Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE).
*/
HasBasicZoom, /**< @brief Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM). */
HasBasicFocus, /**< @brief Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS). */
HasVideoStream, /**< @brief Camera has video streaming capabilities (request
VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video
streaming info). */
HasTrackingPoint, /**< @brief Camera supports tracking of a point on the camera view..
*/
HasTrackingRectangle, /**< @brief Camera supports tracking of a selection rectangle on
the camera view.. */
HasTrackingGeoStatus, /**< @brief Camera supports tracking geo status
(CAMERA_TRACKING_GEO_STATUS).. */
};

/**
* @brief Stream operator to print information about a `Camera::CameraCapFlags`.
*
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, Camera::Information::CameraCapFlags const& camera_cap_flags);

std::string vendor_name{}; /**< @brief Name of the camera vendor */
std::string model_name{}; /**< @brief Name of the camera model */
std::string firmware_version{}; /**< @brief Camera firmware version in
major[.minor[.patch[.dev]]] format */
float focal_length_mm{}; /**< @brief Focal length */
float horizontal_sensor_size_mm{}; /**< @brief Horizontal sensor size */
float vertical_sensor_size_mm{}; /**< @brief Vertical sensor size */
uint32_t horizontal_resolution_px{}; /**< @brief Horizontal image resolution in pixels */
uint32_t vertical_resolution_px{}; /**< @brief Vertical image resolution in pixels */
uint32_t lens_id{}; /**< @brief Lens ID */
uint32_t
definition_file_version{}; /**< @brief Camera definition file version (iteration) */
std::string
definition_file_uri{}; /**< @brief Camera definition URI (http or mavlink ftp) */
std::vector<CameraCapFlags>
camera_cap_flags{}; /**< @brief Camera capability flags (Array) */
};

/**
Expand Down
41 changes: 40 additions & 1 deletion src/mavsdk/plugins/camera_server/camera_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,38 @@ CameraServer::respond_reset_settings(CameraFeedback reset_settings_feedback) con
return _impl->respond_reset_settings(reset_settings_feedback);
}

std::ostream&
operator<<(std::ostream& str, CameraServer::Information::CameraCapFlags const& camera_cap_flags)
{
switch (camera_cap_flags) {
case CameraServer::Information::CameraCapFlags::CaptureVideo:
return str << "Capture Video";
case CameraServer::Information::CameraCapFlags::CaptureImage:
return str << "Capture Image";
case CameraServer::Information::CameraCapFlags::HasModes:
return str << "Has Modes";
case CameraServer::Information::CameraCapFlags::CanCaptureImageInVideoMode:
return str << "Can Capture Image In Video Mode";
case CameraServer::Information::CameraCapFlags::CanCaptureVideoInImageMode:
return str << "Can Capture Video In Image Mode";
case CameraServer::Information::CameraCapFlags::HasImageSurveyMode:
return str << "Has Image Survey Mode";
case CameraServer::Information::CameraCapFlags::HasBasicZoom:
return str << "Has Basic Zoom";
case CameraServer::Information::CameraCapFlags::HasBasicFocus:
return str << "Has Basic Focus";
case CameraServer::Information::CameraCapFlags::HasVideoStream:
return str << "Has Video Stream";
case CameraServer::Information::CameraCapFlags::HasTrackingPoint:
return str << "Has Tracking Point";
case CameraServer::Information::CameraCapFlags::HasTrackingRectangle:
return str << "Has Tracking Rectangle";
case CameraServer::Information::CameraCapFlags::HasTrackingGeoStatus:
return str << "Has Tracking Geo Status";
default:
return str << "Unknown";
}
}
bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs)
{
return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) &&
Expand All @@ -222,7 +254,8 @@ bool operator==(const CameraServer::Information& lhs, const CameraServer::Inform
(rhs.vertical_resolution_px == lhs.vertical_resolution_px) &&
(rhs.lens_id == lhs.lens_id) &&
(rhs.definition_file_version == lhs.definition_file_version) &&
(rhs.definition_file_uri == lhs.definition_file_uri);
(rhs.definition_file_uri == lhs.definition_file_uri) &&
(rhs.camera_cap_flags == lhs.camera_cap_flags);
}

std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information)
Expand All @@ -240,6 +273,12 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf
str << " lens_id: " << information.lens_id << '\n';
str << " definition_file_version: " << information.definition_file_version << '\n';
str << " definition_file_uri: " << information.definition_file_uri << '\n';
str << " camera_cap_flags: [";
for (auto it = information.camera_cap_flags.begin(); it != information.camera_cap_flags.end();
++it) {
str << *it;
str << (it + 1 != information.camera_cap_flags.end() ? ", " : "]\n");
}
str << '}';
return str;
}
Expand Down
Loading
Loading