Skip to content

Commit

Permalink
Add more video streaming info
Browse files Browse the repository at this point in the history
 * unify the camera and camera server stream info;
 * support multi camera video stream info;
 * add camera video stream info usage example;
  • Loading branch information
tbago committed Feb 27, 2024
1 parent f5e6945 commit 02853b2
Show file tree
Hide file tree
Showing 19 changed files with 2,995 additions and 1,457 deletions.
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
39 changes: 39 additions & 0 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 @@ -44,6 +45,9 @@ int main(int argc, char** argv)
.definition_file_uri = "", // TODO: implement this using MAVLink FTP
});

// 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 +179,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});
}
7 changes: 4 additions & 3 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
124 changes: 77 additions & 47 deletions src/mavsdk/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -506,11 +506,6 @@ Camera::Result CameraImpl::stop_video()
{
auto cmd_stop_video = make_command_stop_video();

{
std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
_video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
}

return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video));
}

Expand Down Expand Up @@ -626,9 +621,14 @@ Camera::Result CameraImpl::start_video_streaming(int32_t stream_id)
{
std::lock_guard<std::mutex> lock(_video_stream_info.mutex);

if (_video_stream_info.available &&
_video_stream_info.data.status == Camera::VideoStreamInfo::VideoStreamStatus::InProgress) {
return Camera::Result::InProgress;
if (_video_stream_info.available) {
for (auto& video_stream_info : _video_stream_info.data) {
if (video_stream_info.stream_id == stream_id &&
video_stream_info.status ==
Camera::VideoStreamInfo::VideoStreamStatus::InProgress) {
return Camera::Result::InProgress;
}
}
}

// TODO Check whether we're in video mode
Expand All @@ -654,7 +654,13 @@ Camera::Result CameraImpl::stop_video_streaming(int32_t stream_id)
{
std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
// TODO: check if we can/should do that.
_video_stream_info.data.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
// TODO: the better way is use the video streaming subscribe to get the current
// stream status
for (auto& video_stream_info : _video_stream_info.data) {
if (video_stream_info.stream_id == stream_id) {
video_stream_info.status = Camera::VideoStreamInfo::VideoStreamStatus::NotRunning;
}
}
}
return result;
}
Expand All @@ -665,7 +671,7 @@ void CameraImpl::request_video_stream_info()
_system_impl->send_command_async(make_command_request_video_stream_status(), nullptr);
}

Camera::VideoStreamInfo CameraImpl::video_stream_info()
std::vector<Camera::VideoStreamInfo> CameraImpl::video_stream_info()
{
std::lock_guard<std::mutex> lock(_video_stream_info.mutex);

Expand Down Expand Up @@ -1054,9 +1060,9 @@ void CameraImpl::process_camera_image_captured(const mavlink_message_t& message)
capture_info, [this](const auto& func) { _system_impl->call_user_callback(func); });

if (_capture_info.last_advertised_image_index != -1) {
// Save captured indices that have been dropped to request later, however, don't
// do it from the very beginning as there might be many photos from a previous
// time that we don't want to request.
// Save captured indices that have been dropped to request later, however,
// don't do it from the very beginning as there might be many photos from a
// previous time that we don't want to request.
for (int i = _capture_info.last_advertised_image_index + 1; i < capture_info.index;
++i) {
if (_capture_info.missing_image_retries.find(i) ==
Expand Down Expand Up @@ -1259,24 +1265,41 @@ void CameraImpl::process_video_information(const mavlink_message_t& message)

{
std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
// TODO: use stream_id and count
_video_stream_info.data.status =
mavsdk::Camera::VideoStreamInfo video_stream_info;
video_stream_info.stream_id = received_video_info.stream_id;

video_stream_info.status =
(received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
_video_stream_info.data.spectrum =
video_stream_info.spectrum =
(received_video_info.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);

auto& video_stream_info = _video_stream_info.data.settings;
video_stream_info.frame_rate_hz = received_video_info.framerate;
video_stream_info.horizontal_resolution_pix = received_video_info.resolution_h;
video_stream_info.vertical_resolution_pix = received_video_info.resolution_v;
video_stream_info.bit_rate_b_s = received_video_info.bitrate;
video_stream_info.rotation_deg = received_video_info.rotation;
video_stream_info.horizontal_fov_deg = static_cast<float>(received_video_info.hfov);
video_stream_info.uri = received_video_info.uri;
video_stream_info.settings.frame_rate_hz = received_video_info.framerate;
video_stream_info.settings.horizontal_resolution_pix = received_video_info.resolution_h;
video_stream_info.settings.vertical_resolution_pix = received_video_info.resolution_v;
video_stream_info.settings.bit_rate_b_s = received_video_info.bitrate;
video_stream_info.settings.rotation_deg = received_video_info.rotation;
video_stream_info.settings.horizontal_fov_deg =
static_cast<float>(received_video_info.hfov);
video_stream_info.settings.uri = received_video_info.uri;

bool found = false;
for (auto& it : _video_stream_info.data) {
if (it.stream_id == received_video_info.stream_id) { // video stream info already exits
// copy video stream info
it = video_stream_info;
found = true;
break;
}
}
if (!found) {
_video_stream_info.data.emplace_back(video_stream_info);
}

LogDebug() << "Found " << _video_stream_info.data.size() << " video stream";
_video_stream_info.available = true;
}

Expand All @@ -1289,27 +1312,32 @@ void CameraImpl::process_video_stream_status(const mavlink_message_t& message)
mavlink_msg_video_stream_status_decode(&message, &received_video_stream_status);
{
std::lock_guard<std::mutex> lock(_video_stream_info.mutex);
_video_stream_info.data.status =
(received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
_video_stream_info.data.spectrum =
(received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);

auto& video_stream_info = _video_stream_info.data.settings;
video_stream_info.frame_rate_hz = received_video_stream_status.framerate;
video_stream_info.horizontal_resolution_pix = received_video_stream_status.resolution_h;
video_stream_info.vertical_resolution_pix = received_video_stream_status.resolution_v;
video_stream_info.bit_rate_b_s = received_video_stream_status.bitrate;
video_stream_info.rotation_deg = received_video_stream_status.rotation;
video_stream_info.horizontal_fov_deg =
static_cast<float>(received_video_stream_status.hfov);
_video_stream_info.available = true;
for (auto& video_stream_info : _video_stream_info.data) {
if (video_stream_info.stream_id == received_video_stream_status.stream_id) {
video_stream_info.status =
(received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_RUNNING ?
Camera::VideoStreamInfo::VideoStreamStatus::InProgress :
Camera::VideoStreamInfo::VideoStreamStatus::NotRunning);
video_stream_info.spectrum =
(received_video_stream_status.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL ?
Camera::VideoStreamInfo::VideoStreamSpectrum::Infrared :
Camera::VideoStreamInfo::VideoStreamSpectrum::VisibleLight);

video_stream_info.settings.frame_rate_hz = received_video_stream_status.framerate;
video_stream_info.settings.horizontal_resolution_pix =
received_video_stream_status.resolution_h;
video_stream_info.settings.vertical_resolution_pix =
received_video_stream_status.resolution_v;
video_stream_info.settings.bit_rate_b_s = received_video_stream_status.bitrate;
video_stream_info.settings.rotation_deg = received_video_stream_status.rotation;
video_stream_info.settings.horizontal_fov_deg =
static_cast<float>(received_video_stream_status.hfov);

_video_stream_info.available = true;
notify_video_stream_info();
}
}
}

notify_video_stream_info();
}

void CameraImpl::process_flight_information(const mavlink_message_t& message)
Expand Down Expand Up @@ -1602,7 +1630,8 @@ void CameraImpl::set_option_async(
[temp_callback]() { temp_callback(Camera::Result::Success); });
}

// FIXME: We are already holding the lock when this lambda is run and need to
// FIXME: We are already holding the lock when this lambda is run and need
// to
// schedule the refresh_params() for later.
// We (ab)use the thread pool for the user callbacks for this.
_system_impl->call_user_callback([this]() { refresh_params(); });
Expand Down Expand Up @@ -2064,8 +2093,9 @@ void CameraImpl::list_photos_async(
std::unique_lock<std::mutex> capture_request_lock(_captured_request_mutex);

for (int i = start_index; i < _status.image_count; i++) {
// In case the vehicle sends capture info, but not those we are asking, we do not
// want to loop infinitely. The safety_count is here to abort if this happens.
// In case the vehicle sends capture info, but not those we are asking, we do
// not want to loop infinitely. The safety_count is here to abort if this
// happens.
auto safety_count = 0;
const auto safety_count_boundary = 10;

Expand Down
6 changes: 3 additions & 3 deletions src/mavsdk/plugins/camera/camera_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class CameraImpl : public PluginImplBase {

std::pair<Camera::Result, Camera::VideoStreamInfo> get_video_stream_info();

Camera::VideoStreamInfo video_stream_info();
std::vector<Camera::VideoStreamInfo> video_stream_info();
Camera::VideoStreamInfoHandle
subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback);
void unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle);
Expand Down Expand Up @@ -254,10 +254,10 @@ class CameraImpl : public PluginImplBase {

struct {
std::mutex mutex{};
Camera::VideoStreamInfo data{};
std::vector<Camera::VideoStreamInfo> data{};
bool available{false};
void* call_every_cookie{nullptr};
CallbackList<Camera::VideoStreamInfo> subscription_callbacks{};
CallbackList<std::vector<Camera::VideoStreamInfo>> subscription_callbacks{};
} _video_stream_info{};

struct {
Expand Down
11 changes: 6 additions & 5 deletions src/mavsdk/plugins/camera/include/plugins/camera/camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -298,6 +298,7 @@ class Camera : public PluginBase {
std::ostream& str,
Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum);

int32_t stream_id{}; /**< @brief stream unique id */
VideoStreamSettings settings{}; /**< @brief Video stream settings */
VideoStreamStatus status{}; /**< @brief Current status of video streaming */
VideoStreamSpectrum spectrum{}; /**< @brief Light-spectrum of the video stream */
Expand Down Expand Up @@ -704,12 +705,12 @@ class Camera : public PluginBase {
/**
* @brief Callback type for subscribe_video_stream_info.
*/
using VideoStreamInfoCallback = std::function<void(VideoStreamInfo)>;
using VideoStreamInfoCallback = std::function<void(std::vector<VideoStreamInfo>)>;

/**
* @brief Handle type for subscribe_video_stream_info.
*/
using VideoStreamInfoHandle = Handle<VideoStreamInfo>;
using VideoStreamInfoHandle = Handle<std::vector<VideoStreamInfo>>;

/**
* @brief Subscribe to video stream info updates.
Expand All @@ -722,11 +723,11 @@ class Camera : public PluginBase {
void unsubscribe_video_stream_info(VideoStreamInfoHandle handle);

/**
* @brief Poll for 'VideoStreamInfo' (blocking).
* @brief Poll for 'std::vector<VideoStreamInfo>' (blocking).
*
* @return One VideoStreamInfo update.
* @return One std::vector<VideoStreamInfo> update.
*/
VideoStreamInfo video_stream_info() const;
std::vector<VideoStreamInfo> video_stream_info() const;

/**
* @brief Callback type for subscribe_capture_info.
Expand Down
Loading

0 comments on commit 02853b2

Please sign in to comment.