Skip to content

Commit

Permalink
camera: move interval integration test to system tests
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 28, 2024
1 parent 6bb7560 commit c235318
Show file tree
Hide file tree
Showing 5 changed files with 81 additions and 151 deletions.
83 changes: 0 additions & 83 deletions src/integration_tests/camera_take_photo_interval.cpp

This file was deleted.

65 changes: 0 additions & 65 deletions src/mavsdk/plugins/camera/mocks/camera_mock.h

This file was deleted.

1 change: 1 addition & 0 deletions src/system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand Down
5 changes: 2 additions & 3 deletions src/system_tests/camera_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()};

Expand Down Expand Up @@ -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) {
Expand Down
78 changes: 78 additions & 0 deletions src/system_tests/camera_take_photo_interval.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
#include "mavsdk.h"
#include "plugins/camera/camera.h"
#include "plugins/camera_server/camera_server.h"
#include "log.h"
#include <future>
#include <mutex>
#include <thread>
#include <gtest/gtest.h>

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<std::shared_ptr<System>>();
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);
}

0 comments on commit c235318

Please sign in to comment.