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 all commits
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
8 changes: 8 additions & 0 deletions examples/camera_server/camera_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,14 @@ int main(int argc, const char* argv[])
std::cout << info << std::endl;
});

camera.subscribe_video_stream_info(
[](std::vector<mavsdk::Camera::VideoStreamInfo> video_stream_infos) {
std::cout << "Camera Video stream information:" << std::endl;
for (auto& stream_info : video_stream_infos) {
std::cout << stream_info << std::endl;
}
});

camera.subscribe_status([](mavsdk::Camera::Status status) {
std::cout << "Camera status:" << std::endl;
std::cout << status << std::endl;
Expand Down
52 changes: 49 additions & 3 deletions examples/camera_server/camera_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <mavsdk/plugins/camera_server/camera_server.h>

static void subscribe_camera_operation(mavsdk::CameraServer& camera_server);
static void SetVideoStreamInfo(mavsdk::CameraServer& camera_server);

int main(int argc, char** argv)
{
Expand Down Expand Up @@ -33,17 +34,27 @@ 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
SetVideoStreamInfo(camera_server);

if (ret != mavsdk::CameraServer::Result::Success) {
std::cerr << "Failed to set camera info, exiting" << std::endl;
return 2;
Expand Down Expand Up @@ -175,4 +186,39 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server)
std::cout << "reset camera settings" << std::endl;
camera_server.respond_reset_settings(mavsdk::CameraServer::CameraFeedback::Ok);
});
}

static void SetVideoStreamInfo(mavsdk::CameraServer& camera_server)
{
mavsdk::CameraServer::VideoStreamInfo normal_video_stream;
normal_video_stream.stream_id = 1;

normal_video_stream.settings.frame_rate_hz = 60.0;
normal_video_stream.settings.horizontal_resolution_pix = 1920;
normal_video_stream.settings.vertical_resolution_pix = 1080;
normal_video_stream.settings.bit_rate_b_s = 4 * 1024 * 1024;
normal_video_stream.settings.rotation_deg = 1;
normal_video_stream.settings.uri = "rtsp://192.168.0.1/live";
normal_video_stream.settings.horizontal_fov_deg = 1;
normal_video_stream.status =
mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::InProgress;
normal_video_stream.spectrum =
mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::VisibleLight;

mavsdk::CameraServer::VideoStreamInfo infrared_video_stream;
infrared_video_stream.stream_id = 2;

infrared_video_stream.settings.frame_rate_hz = 24.0;
infrared_video_stream.settings.horizontal_resolution_pix = 1280;
infrared_video_stream.settings.vertical_resolution_pix = 720;
infrared_video_stream.settings.bit_rate_b_s = 4 * 1024;
infrared_video_stream.settings.rotation_deg = 2;
infrared_video_stream.settings.uri = "rtsp://192.168.0.1/live2";
infrared_video_stream.settings.horizontal_fov_deg = 2;
infrared_video_stream.status =
mavsdk::CameraServer::VideoStreamInfo::VideoStreamStatus::NotRunning;
infrared_video_stream.spectrum =
mavsdk::CameraServer::VideoStreamInfo::VideoStreamSpectrum::Infrared;

auto ret = camera_server.set_video_stream_info({normal_video_stream, infrared_video_stream});
}
56 changes: 52 additions & 4 deletions src/mavsdk/plugins/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ void Camera::unsubscribe_video_stream_info(VideoStreamInfoHandle handle)
_impl->unsubscribe_video_stream_info(handle);
}

Camera::VideoStreamInfo Camera::video_stream_info() const
std::vector<Camera::VideoStreamInfo> Camera::video_stream_info() const
{
return _impl->video_stream_info();
}
Expand Down Expand Up @@ -437,14 +437,15 @@ std::ostream& operator<<(
}
bool operator==(const Camera::VideoStreamInfo& lhs, const Camera::VideoStreamInfo& rhs)
{
return (rhs.settings == lhs.settings) && (rhs.status == lhs.status) &&
(rhs.spectrum == lhs.spectrum);
return (rhs.stream_id == lhs.stream_id) && (rhs.settings == lhs.settings) &&
(rhs.status == lhs.status) && (rhs.spectrum == lhs.spectrum);
}

std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info)
{
str << std::setprecision(15);
str << "video_stream_info:" << '\n' << "{\n";
str << " stream_id: " << video_stream_info.stream_id << '\n';
str << " settings: " << video_stream_info.settings << '\n';
str << " status: " << video_stream_info.status << '\n';
str << " spectrum: " << video_stream_info.spectrum << '\n';
Expand Down Expand Up @@ -578,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 @@ -589,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 @@ -598,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
Loading
Loading