diff --git a/src/integration_tests/CMakeLists.txt b/src/integration_tests/CMakeLists.txt index 3ca271027e..f474d7b476 100644 --- a/src/integration_tests/CMakeLists.txt +++ b/src/integration_tests/CMakeLists.txt @@ -30,6 +30,7 @@ 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 diff --git a/src/integration_tests/camera_capture_info.cpp b/src/integration_tests/camera_capture_info.cpp new file mode 100644 index 0000000000..c8c1707adb --- /dev/null +++ b/src/integration_tests/camera_capture_info.cpp @@ -0,0 +1,37 @@ +#include "integration_test_helper.h" +#include "mavsdk.h" +#include +#include +#include +#include "plugins/camera/camera.h" + +using namespace mavsdk; + +TEST(CameraTest, CaptureInfo) +{ + Mavsdk mavsdk; + + ConnectionResult ret = mavsdk.add_udp_connection(); + ASSERT_EQ(ret, ConnectionResult::Success); + + // Wait for system to connect via heartbeat. + std::this_thread::sleep_for(std::chrono::seconds(2)); + + ASSERT_EQ(mavsdk.systems().size(), 1); + + auto system = mavsdk.systems().at(0); + auto camera = Camera{system}; + + std::this_thread::sleep_for(std::chrono::seconds(2)); + + EXPECT_EQ(camera.take_photo(), Camera::Result::Success); + + bool received_capture_info = false; + camera.subscribe_capture_info([&received_capture_info](Camera::CaptureInfo capture_info) { + received_capture_info = true; + LogInfo() << capture_info; + }); + + std::this_thread::sleep_for(std::chrono::seconds(5)); + EXPECT_TRUE(received_capture_info); +}