diff --git a/src/integration_tests/camera_take_photo_interval.cpp b/src/integration_tests/camera_take_photo_interval.cpp deleted file mode 100644 index 32ebc88b6..000000000 --- a/src/integration_tests/camera_take_photo_interval.cpp +++ /dev/null @@ -1,83 +0,0 @@ -#include -#include -#include -#include -#include -#include "integration_test_helper.h" -#include "mavsdk.h" -#include "system.h" - -using namespace mavsdk; -static void receive_camera_result(Camera::Result result); - -static void check_interval_on(std::shared_ptr camera, bool on); - -static std::atomic _received_result{false}; - -TEST(CameraTest, TakePhotoInterval) -{ - Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; - - ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - // We want to take the pictures in photo mode. - camera->set_mode(Camera::Mode::Photo); - - check_interval_on(camera, false); - - std::this_thread::sleep_for(std::chrono::seconds(1)); - - _received_result = false; - camera->start_photo_interval_async( - 2.0f, [](Camera::Result result) { return receive_camera_result(result); }); - - // Wait for 3 photos - std::this_thread::sleep_for(std::chrono::seconds(7)); - - check_interval_on(camera, true); - - // Wait for another photo - std::this_thread::sleep_for(std::chrono::seconds(2)); - - // Then, stop it again. - camera->stop_photo_interval_async( - [](Camera::Result result) { return receive_camera_result(result); }); - - std::this_thread::sleep_for(std::chrono::seconds(1)); - check_interval_on(camera, false); - - EXPECT_TRUE(_received_result); -} - -void receive_camera_result(Camera::Result result) -{ - _received_result = true; - EXPECT_EQ(result, Camera::Result::Success); -} - -void check_interval_on(std::shared_ptr camera, bool on) -{ - auto prom = std::make_shared>(); - auto ret = prom->get_future(); - - // Check if status is correct - Camera::StatusHandle handle = - camera->subscribe_status([prom, on, camera, &handle](Camera::Status status) { - camera->unsubscribe_status(handle); - EXPECT_EQ(status.photo_interval_on, on); - prom->set_value(); - }); - - // Block now for a while to wait for result. - auto status = ret.wait_for(std::chrono::seconds(2)); - - EXPECT_EQ(status, std::future_status::ready); -} diff --git a/src/mavsdk/plugins/camera/mocks/camera_mock.h b/src/mavsdk/plugins/camera/mocks/camera_mock.h deleted file mode 100644 index d9ec17469..000000000 --- a/src/mavsdk/plugins/camera/mocks/camera_mock.h +++ /dev/null @@ -1,65 +0,0 @@ -#include - -#include "plugins/camera/camera.h" - -namespace mavsdk { -namespace testing { - -class MockCamera { -public: - MOCK_CONST_METHOD0(prepare, Camera::Result()){}; - MOCK_CONST_METHOD0(take_photo, Camera::Result()){}; - MOCK_CONST_METHOD1(start_photo_interval, Camera::Result(const float)){}; - MOCK_CONST_METHOD0(stop_photo_interval, Camera::Result()){}; - MOCK_CONST_METHOD0(start_video, Camera::Result()){}; - MOCK_CONST_METHOD0(stop_video, Camera::Result()){}; - MOCK_CONST_METHOD1(start_video_streaming, Camera::Result(int32_t stream_id)){}; - MOCK_CONST_METHOD1(stop_video_streaming, Camera::Result(int32_t strema_id)){}; - MOCK_CONST_METHOD1(set_mode, Camera::Result(Camera::Mode)){}; - MOCK_CONST_METHOD1(set_setting, Camera::Result(Camera::Setting)){}; - MOCK_CONST_METHOD1(get_setting, std::pair(Camera::Setting)){}; - MOCK_CONST_METHOD1(subscribe_mode, Camera::ModeHandle(Camera::ModeCallback)){}; - MOCK_CONST_METHOD1(unsubscribe_mode, void(Camera::ModeHandle)){}; - MOCK_CONST_METHOD1(set_video_stream_settings, void(Camera::VideoStreamSettings)){}; - MOCK_CONST_METHOD1( - subscribe_video_stream_info, - Camera::VideoStreamInfoHandle(Camera::VideoStreamInfoCallback)){}; - MOCK_CONST_METHOD1(unsubscribe_video_stream_info, void(Camera::VideoStreamInfoHandle)){}; - MOCK_CONST_METHOD1( - subscribe_capture_info, Camera::CaptureInfoHandle(Camera::CaptureInfoCallback)){}; - MOCK_CONST_METHOD1(unsubscribe_capture_info, void(Camera::CaptureInfoHandle)){}; - MOCK_CONST_METHOD1(subscribe_storage, Camera::StorageHandle(Camera::StorageCallback)){}; - MOCK_CONST_METHOD1(unsubscribe_storage, void(Camera::StorageHandle)){}; - MOCK_CONST_METHOD1( - subscribe_current_settings, - Camera::CurrentSettingsHandle(Camera::CurrentSettingsCallback)){}; - MOCK_CONST_METHOD1(unsubscribe_current_settings, void(Camera::CurrentSettingsHandle)){}; - MOCK_CONST_METHOD1( - subscribe_possible_setting_options, - Camera::PossibleSettingOptionsHandle(Camera::PossibleSettingOptionsCallback)){}; - MOCK_CONST_METHOD1( - unsubscribe_possible_setting_options, void(Camera::PossibleSettingOptionsHandle)){}; - MOCK_CONST_METHOD3( - set_option_async, void(Camera::ResultCallback, const std::string&, const Camera::Option)){}; - MOCK_CONST_METHOD1(format_storage, Camera::Result(int32_t)){}; - MOCK_CONST_METHOD1( - list_photos, - std::pair>(Camera::PhotosRange)){}; - MOCK_CONST_METHOD1(select_camera, Camera::Result(int32_t)){}; - MOCK_CONST_METHOD0(reset_settings, Camera::Result()){}; - - MOCK_CONST_METHOD0(zoom_in_start, Camera::Result()){}; - MOCK_CONST_METHOD0(zoom_out_start, Camera::Result()){}; - MOCK_CONST_METHOD0(zoom_stop, Camera::Result()){}; - MOCK_CONST_METHOD1(zoom_range, Camera::Result(float)){}; - MOCK_CONST_METHOD3(track_point, Camera::Result(float, float, float)){}; - MOCK_CONST_METHOD4(track_rectangle, Camera::Result(float, float, float, float)){}; - MOCK_CONST_METHOD0(track_stop, Camera::Result()){}; - MOCK_CONST_METHOD0(focus_in_start, Camera::Result()){}; - MOCK_CONST_METHOD0(focus_out_start, Camera::Result()){}; - MOCK_CONST_METHOD1(focus_stop, Camera::Result(int32_t)){}; - MOCK_CONST_METHOD2(focus_range, Camera::Result(int32_t, float)){}; -}; - -} // namespace testing -} // namespace mavsdk diff --git a/src/system_tests/CMakeLists.txt b/src/system_tests/CMakeLists.txt index c1e0c5db8..585bdf01c 100644 --- a/src/system_tests/CMakeLists.txt +++ b/src/system_tests/CMakeLists.txt @@ -1,5 +1,6 @@ add_executable(system_tests_runner camera_take_photo.cpp + camera_take_photo_interval.cpp camera_format_storage.cpp camera_settings.cpp camera_storage.cpp diff --git a/src/system_tests/camera_storage.cpp b/src/system_tests/camera_storage.cpp index 439816e4d..3969f7133 100644 --- a/src/system_tests/camera_storage.cpp +++ b/src/system_tests/camera_storage.cpp @@ -19,8 +19,7 @@ TEST(SystemTest, CameraStorage) mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), ConnectionResult::Success); ASSERT_EQ( - mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), - ConnectionResult::Success); + mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); auto camera_server = CameraServer{mavsdk_camera.server_component()}; @@ -66,7 +65,7 @@ TEST(SystemTest, CameraStorage) }); bool got_storage = false; - for (unsigned i = 0; i < 10; ++i) { + for (unsigned i = 0; i < 60; ++i) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); auto ret = camera.get_storage(1); if (ret.first == Camera::Result::Unavailable) { diff --git a/src/system_tests/camera_take_photo_interval.cpp b/src/system_tests/camera_take_photo_interval.cpp new file mode 100644 index 000000000..fe4dd5211 --- /dev/null +++ b/src/system_tests/camera_take_photo_interval.cpp @@ -0,0 +1,78 @@ +#include "mavsdk.h" +#include "plugins/camera/camera.h" +#include "plugins/camera_server/camera_server.h" +#include "log.h" +#include +#include +#include +#include + +using namespace mavsdk; + +TEST(SystemTest, CameraTakePhotoInterval) +{ + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; + + Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}}; + + ASSERT_EQ( + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), + ConnectionResult::Success); + ASSERT_EQ( + mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); + + auto camera_server = CameraServer{mavsdk_camera.server_component()}; + + CameraServer::Information information{}; + information.vendor_name = "CoolCameras"; + information.model_name = "Frozen Super"; + information.firmware_version = "4.0.0"; + information.definition_file_version = 1; + information.definition_file_uri = ""; + camera_server.set_information(information); + + camera_server.subscribe_take_photo([&camera_server](int32_t index) { + LogInfo() << "Let's take photo " << index; + + CameraServer::CaptureInfo info; + info.index = index; + info.is_success = true; + + camera_server.respond_take_photo(CameraServer::CameraFeedback::Ok, info); + }); + + auto prom = std::promise>(); + auto fut = prom.get_future(); + std::once_flag flag; + + auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { + const auto system = mavsdk_groundstation.systems().back(); + if (system->is_connected() && system->has_camera()) { + std::call_once(flag, [&]() { prom.set_value(system); }); + } + }); + + ASSERT_EQ(fut.wait_for(std::chrono::seconds(10)), std::future_status::ready); + mavsdk_groundstation.unsubscribe_on_new_system(handle); + auto system = fut.get(); + + auto camera = Camera{system}; + + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + // We expect to find one camera. + ASSERT_EQ(camera.camera_list().cameras.size(), 1); + + unsigned captured = 0; + + Camera::CaptureInfoHandle capture_handle = camera.subscribe_capture_info( + [&](Camera::CaptureInfo capture_info) { + LogInfo() << "Received captured info for image: " << capture_info.index; + ++captured; + }); + + EXPECT_EQ(camera.start_photo_interval(1, 0.1f), Camera::Result::Success); + + std::this_thread::sleep_for(std::chrono::milliseconds(250)); + EXPECT_EQ(camera.stop_photo_interval(1), Camera::Result::Success); + EXPECT_GE(captured, 2); +}