Skip to content

Commit

Permalink
Merge pull request #2386 from mavlink/pr-multiple-cameras
Browse files Browse the repository at this point in the history
camera: support multiple cameras within one instance
  • Loading branch information
julianoes authored Dec 18, 2024
2 parents 5f2f56d + 2e0e121 commit fb5bd98
Show file tree
Hide file tree
Showing 110 changed files with 33,214 additions and 20,478 deletions.
18 changes: 16 additions & 2 deletions examples/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,22 @@ int main(int argc, char** argv)
auto telemetry = Telemetry{system};
auto camera = Camera{system};

// Wait for camera to be discovered.
std::this_thread::sleep_for(std::chrono::milliseconds(500));

// We expect to find one camera.
if (camera.camera_list().cameras.size() == 0) {
std::cerr << "No camera found, exiting.\n";
return 1;
}

if (camera.camera_list().cameras.size() > 1) {
std::cout << "More than one camera found, using first one discovered.\n";
}
const auto component_id = camera.camera_list().cameras[0].component_id;

// First, make sure camera is in photo mode.
const auto mode_result = camera.set_mode(Camera::Mode::Photo);
const auto mode_result = camera.set_mode(component_id, Camera::Mode::Photo);
if (mode_result != Camera::Result::Success) {
std::cerr << "Could not switch to Photo mode: " << mode_result;
return 1;
Expand All @@ -85,7 +99,7 @@ int main(int argc, char** argv)
std::cout << "Image captured, stored at: " << capture_info.file_url << '\n';
});

const auto photo_result = camera.take_photo();
const auto photo_result = camera.take_photo(component_id);
if (photo_result != Camera::Result::Success) {
std::cerr << "Taking Photo failed: " << mode_result;
return 1;
Expand Down
54 changes: 36 additions & 18 deletions examples/camera_server/camera_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <mavsdk/mavsdk.h>
#include <mavsdk/plugins/camera/camera.h>

static void do_camera_operation(mavsdk::Camera& camera);
static void do_camera_operation(int32_t component_id, mavsdk::Camera& camera);

int main(int argc, const char* argv[])
{
Expand Down Expand Up @@ -44,17 +44,35 @@ int main(int argc, const char* argv[])
auto system = fut.get();

auto camera = mavsdk::Camera{system};
camera.subscribe_information([](mavsdk::Camera::Information info) {
std::cout << "Camera information:" << std::endl;
std::cout << info << std::endl;

camera.subscribe_camera_list([](mavsdk::Camera::CameraList list) {
std::cout << "Cameras found:" << std::endl;
for (auto& camera : list.cameras) {
std::cout << camera << '\n';
}
});

camera.subscribe_status([](mavsdk::Camera::Status status) {
std::cout << "Camera status:" << std::endl;
std::cout << status << std::endl;
// Wait for camera to be discovered.
std::this_thread::sleep_for(std::chrono::milliseconds(500));

// We expect to find one camera.
if (camera.camera_list().cameras.size() == 0) {
std::cerr << "No camera found, exiting.\n";
return 1;
}

if (camera.camera_list().cameras.size() > 1) {
std::cout << "More than one camera found, using first one discovered.\n";
}

const auto component_id = camera.camera_list().cameras[0].component_id;

camera.subscribe_storage([](mavsdk::Camera::StorageUpdate update) {
std::cout << "Camera storage update:" << std::endl;
std::cout << update << std::endl;
});

do_camera_operation(camera);
do_camera_operation(component_id, camera);

// for test subscribe camera status, so don't end the process
while (true) {
Expand All @@ -63,36 +81,36 @@ int main(int argc, const char* argv[])
return 0;
}

void do_camera_operation(mavsdk::Camera& camera)
void do_camera_operation(int32_t component_id, mavsdk::Camera& camera)
{
// switch to photo mode to take photo
auto operation_result = camera.set_mode(mavsdk::Camera::Mode::Photo);
auto operation_result = camera.set_mode(component_id, mavsdk::Camera::Mode::Photo);
std::cout << "Set camera to photo mode result : " << operation_result << std::endl;

operation_result = camera.take_photo();
operation_result = camera.take_photo(component_id);
std::cout << "Take photo result : " << operation_result << std::endl;

// switch to video mode to recording video
operation_result = camera.set_mode(mavsdk::Camera::Mode::Video);
operation_result = camera.set_mode(component_id, mavsdk::Camera::Mode::Video);
std::cout << "Set camera to video mode result : " << operation_result << std::endl;

operation_result = camera.start_video();
operation_result = camera.start_video(component_id);
std::cout << "Start video result : " << operation_result << std::endl;

operation_result = camera.stop_video();
operation_result = camera.stop_video(component_id);
std::cout << "Stop video result : " << operation_result << std::endl;

// the camera can have multi video stream so may need the stream id
operation_result = camera.start_video_streaming(2);
operation_result = camera.start_video_streaming(component_id, 0);
std::cout << "start video streaming result : " << operation_result << std::endl;

operation_result = camera.stop_video_streaming(2);
operation_result = camera.stop_video_streaming(component_id, 0);
std::cout << "stop video streaming result : " << operation_result << std::endl;

// format the storage with special storage id test
operation_result = camera.format_storage(11);
operation_result = camera.format_storage(component_id, 0);
std::cout << "format storage result : " << operation_result << std::endl;

operation_result = camera.reset_settings();
operation_result = camera.reset_settings(component_id);
std::cout << "Reset camera settings result : " << operation_result << std::endl;
}
52 changes: 38 additions & 14 deletions examples/camera_settings/camera_settings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ void show_settings(const CurrentSettings& current_settings)
}
}

void change_camera_mode(Camera& camera)
void change_camera_mode(int32_t component_id, Camera& camera)
{
while (true) {
std::cout << "Possible modes:\n"
Expand All @@ -60,21 +60,28 @@ void change_camera_mode(Camera& camera)
std::cin >> input;

if (input == "1") {
camera.set_mode(Camera::Mode::Photo);
camera.set_mode(component_id, Camera::Mode::Photo);
return;
} else if (input == "2") {
camera.set_mode(Camera::Mode::Video);
camera.set_mode(component_id, Camera::Mode::Video);
return;
}
}
}

bool choose_setting(
Camera& camera, const std::string& setting_id, const std::string& current_option_id)
int32_t component_id,
Camera& camera,
const std::string& setting_id,
const std::string& current_option_id)
{
const auto setting_options = camera.possible_setting_options();
const auto setting_options = camera.get_possible_setting_options(component_id);
if (setting_options.first != Camera::Result::Success) {
std::cerr << "Could not get settings\n";
return false;
}

for (const auto& setting_option : setting_options) {
for (const auto& setting_option : setting_options.second) {
if (setting_option.setting_id == setting_id) {
std::cout << "Options for " << setting_option.setting_description << ":\n";
unsigned index = 1;
Expand Down Expand Up @@ -108,15 +115,16 @@ bool choose_setting(
setting.setting_id = setting_id;
setting.option.option_id = setting_option.options[input_int].option_id;

camera.set_setting(setting);
camera.set_setting(component_id, setting);
return true;
}
}

return false;
}

void change_camera_setting(Camera& camera, const CurrentSettings& current_settings)
void change_camera_setting(
int32_t component_id, Camera& camera, const CurrentSettings& current_settings)
{
while (true) {
std::cout << "Possible settings:\n";
Expand Down Expand Up @@ -153,6 +161,7 @@ void change_camera_setting(Camera& camera, const CurrentSettings& current_settin
}

if (choose_setting(
component_id,
camera,
temp_settings[input_int].setting_id,
temp_settings[input_int].option.option_id)) {
Expand Down Expand Up @@ -237,24 +246,39 @@ int main(int argc, char** argv)
auto telemetry = Telemetry{system};
auto camera = Camera{system};

// Wait for camera to be discovered.
std::this_thread::sleep_for(std::chrono::milliseconds(500));

// We expect to find one camera.
if (camera.camera_list().cameras.size() == 0) {
std::cerr << "No camera found, exiting.\n";
return 1;
}

if (camera.camera_list().cameras.size() > 1) {
std::cout << "More than one camera found, using first one discovered.\n";
}
const auto component_id = camera.camera_list().cameras[0].component_id;

CurrentSettings current_settings;

// Subscribe to current settings and cache them.
camera.subscribe_current_settings([&current_settings](std::vector<Camera::Setting> settings) {
std::lock_guard<std::mutex> lock(current_settings.mutex);
current_settings.settings = settings;
});
camera.subscribe_current_settings(
[&current_settings](const Camera::CurrentSettingsUpdate& update) {
std::lock_guard<std::mutex> lock(current_settings.mutex);
current_settings.settings = update.current_settings;
});

while (true) {
switch (get_input()) {
case Input::PrintCurrentSettings:
show_settings(current_settings);
break;
case Input::ChangeCameraMode:
change_camera_mode(camera);
change_camera_mode(component_id, camera);
break;
case Input::ChangeSetting:
change_camera_setting(camera, current_settings);
change_camera_setting(component_id, camera, current_settings);
break;
case Input::Quit:
return 0;
Expand Down
26 changes: 20 additions & 6 deletions examples/camera_zoom/camera_zoom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,22 @@ int main(int argc, char** argv)
// Instantiate plugins.
auto camera = Camera{system};

// Wait for camera to be discovered.
std::this_thread::sleep_for(std::chrono::milliseconds(500));

// We expect to find one camera.
if (camera.camera_list().cameras.size() == 0) {
std::cerr << "No camera found, exiting.\n";
return 1;
}

if (camera.camera_list().cameras.size() > 1) {
std::cout << "More than one camera found, using first one discovered.\n";
}
const auto component_id = camera.camera_list().cameras[0].component_id;

// Zoom in
auto result = camera.zoom_range(2.0f);
auto result = camera.zoom_range(component_id, 2.0f);
if (result != Camera::Result::Success) {
std::cerr << "Zooming failed: " << result << '\n';
return 1;
Expand All @@ -83,7 +97,7 @@ int main(int argc, char** argv)
sleep_for(seconds(4));

// Now try continuous zooming in.
result = camera.zoom_in_start();
result = camera.zoom_in_start(component_id);
if (result != Camera::Result::Success) {
std::cerr << "Zooming in failed: " << result << '\n';
return 1;
Expand All @@ -92,7 +106,7 @@ int main(int argc, char** argv)
sleep_for(seconds(1));

// Now try stopping.
result = camera.zoom_stop();
result = camera.zoom_stop(component_id);
if (result != Camera::Result::Success) {
std::cerr << "Stop zooming failed: " << result << '\n';
return 1;
Expand All @@ -101,7 +115,7 @@ int main(int argc, char** argv)
sleep_for(seconds(1));

// And back out.
result = camera.zoom_out_start();
result = camera.zoom_out_start(component_id);
if (result != Camera::Result::Success) {
std::cerr << "Zooming out failed: " << result << '\n';
return 1;
Expand All @@ -110,7 +124,7 @@ int main(int argc, char** argv)
sleep_for(seconds(1));

// Stop again.
result = camera.zoom_stop();
result = camera.zoom_stop(component_id);
if (result != Camera::Result::Success) {
std::cerr << "Stop zooming failed: " << result << '\n';
return 1;
Expand All @@ -119,7 +133,7 @@ int main(int argc, char** argv)
sleep_for(seconds(1));

// Zoom back out
result = camera.zoom_range(1.0f);
result = camera.zoom_range(component_id, 1.0f);
if (result != Camera::Result::Success) {
std::cerr << "Zooming failed: " << result << '\n';
return 1;
Expand Down
2 changes: 1 addition & 1 deletion proto
10 changes: 0 additions & 10 deletions src/integration_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,21 +11,11 @@ add_executable(integration_tests_runner
action_goto.cpp
action_hold.cpp
calibration.cpp
camera_capture_info.cpp
camera_mode.cpp
camera_settings.cpp
camera_status.cpp
camera_take_photo.cpp
camera_take_photo_interval.cpp
camera_format.cpp
camera_reset_settings.cpp
camera_test_helpers.cpp
connection.cpp
follow_me.cpp
geofence.cpp
info.cpp
offboard_attitude.cpp
#logging.cpp # Not fully implemented
log_files.cpp
mission_cancellation.cpp
mission_change_speed.cpp
Expand Down
39 changes: 0 additions & 39 deletions src/integration_tests/camera_capture_info.cpp

This file was deleted.

Loading

0 comments on commit fb5bd98

Please sign in to comment.