Skip to content

Commit

Permalink
better system tests
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 1, 2024
1 parent 49fac96 commit 0aeeb3d
Show file tree
Hide file tree
Showing 8 changed files with 53 additions and 27 deletions.
2 changes: 1 addition & 1 deletion src/mavsdk/core/http_loader.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class HttpLoader {
HttpLoader(const std::shared_ptr<ICurlWrapper>& curl_wrapper);
#endif

explicit HttpLoader();
HttpLoader();
~HttpLoader();

void start();
Expand Down
6 changes: 1 addition & 5 deletions src/mavsdk/plugins/camera/camera_definition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,6 @@

namespace mavsdk {

CameraDefinition::CameraDefinition() {}

CameraDefinition::~CameraDefinition() {}

bool CameraDefinition::load_file(const std::string& filepath)
{
tinyxml2::XMLError xml_error = _doc.LoadFile(filepath.c_str());
Expand Down Expand Up @@ -542,7 +538,7 @@ bool CameraDefinition::get_possible_settings_locked(
settings[setting.first] = setting.second.value;
}

return (settings.size() > 0);
return !settings.empty();
}

bool CameraDefinition::set_setting(const std::string& name, const ParamValue& value)
Expand Down
4 changes: 2 additions & 2 deletions src/mavsdk/plugins/camera/camera_definition.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@ namespace mavsdk {

class CameraDefinition {
public:
CameraDefinition();
~CameraDefinition();
CameraDefinition() = default;
~CameraDefinition() = default;

bool load_file(const std::string& filepath);
bool load_string(const std::string& content);
Expand Down
33 changes: 23 additions & 10 deletions src/mavsdk/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -889,9 +889,12 @@ void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, C
// different from {PHOTO, VIDEO}, in which case the mode received from
// CAMERA_SETTINGS will be wrong.

if (!potential_camera.camera_definition) {
return;
}

ParamValue value;
if (potential_camera.camera_definition &&
potential_camera.camera_definition->get_setting("CAM_MODE", value)) {
if (potential_camera.camera_definition->get_setting("CAM_MODE", value)) {
if (value.is<uint8_t>()) {
value.set<uint8_t>(static_cast<uint8_t>(mode));
} else if (value.is<int8_t>()) {
Expand Down Expand Up @@ -1298,7 +1301,8 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
const std::string url = potential_camera.camera_definition_url;

if (potential_camera.camera_definition_url.empty()) {
return;
potential_camera.camera_definition_result = Camera::Result::SettingsUnavailable;
notify_camera_list();
}

const auto& info = potential_camera.maybe_information.value();
Expand All @@ -1314,6 +1318,9 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
if (cached_file_option) {
LogDebug() << "Using cached file " << cached_file_option.value();
load_camera_definition_with_lock(potential_camera, cached_file_option.value());
potential_camera.is_fetching_camera_definition = false;
potential_camera.camera_definition_result = Camera::Result::Success;
notify_camera_list();

} else {
potential_camera.is_fetching_camera_definition = true;
Expand All @@ -1324,12 +1331,14 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported;
notify_camera_list();
#else
HttpLoader http_loader;
if (_http_loader == nullptr) {
_http_loader = std::make_unique<HttpLoader>();
}
LogInfo() << "Downloading camera definition from: " << url;

auto camera_id = camera_id_for_potential_camera_with_lock(potential_camera);

http_loader.download_async(
_http_loader->download_async(
url,
download_path,
[download_path, file_cache_tag, camera_id, this](
Expand Down Expand Up @@ -1382,11 +1391,15 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
MavlinkFtpClient::ClientResult client_result,
MavlinkFtpClient::ProgressData progress_data) mutable {
// TODO: check if we still exist
LogDebug() << "Mavlink FTP download progress: "
<< 100 * progress_data.bytes_transferred / progress_data.total_bytes
<< " %";
if (client_result == MavlinkFtpClient::ClientResult::Next) {
return;
if (client_result == MavlinkFtpClient::ClientResult::Success ||
client_result == MavlinkFtpClient::ClientResult::Next) {
LogDebug()
<< "Mavlink FTP download progress: "
<< 100 * progress_data.bytes_transferred / progress_data.total_bytes
<< " %";
if (client_result == MavlinkFtpClient::ClientResult::Next) {
return;
}
}

std::lock_guard lock(_mutex);
Expand Down
2 changes: 2 additions & 0 deletions src/mavsdk/plugins/camera/camera_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -388,6 +388,8 @@ class CameraImpl : public PluginImplBase {

std::condition_variable _captured_request_cv;
std::mutex _captured_request_mutex;

std::unique_ptr<HttpLoader> _http_loader{nullptr};
};

} // namespace mavsdk
10 changes: 7 additions & 3 deletions src/system_tests/camera_definition.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include "mavsdk.h"
#include "plugins/camera/camera.h"
#include "plugins/camera_server/camera_server.h"
#include "plugins/ftp_server/ftp_server.h"
#include "log.h"
#include <future>
#include <mutex>
Expand All @@ -21,16 +22,19 @@ TEST(SystemTest, CameraDefinition)
ASSERT_EQ(
mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success);

auto ftp_server = FtpServer{mavsdk_camera.server_component()};

EXPECT_EQ(ftp_server.set_root_dir("src/plugins/camera/"), FtpServer::Result::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 =
"https://raw.githubusercontent.com/mavlink/MAVSDK/main/src/mavsdk/plugins/camera/e90_unit_test.xml";
camera_server.set_information(information);
information.definition_file_uri = "mavlinkftp://e90_unit_test.xml";
EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success);

auto prom = std::promise<std::shared_ptr<System>>();
auto fut = prom.get_future();
Expand Down
6 changes: 2 additions & 4 deletions src/system_tests/camera_list_cameras.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,7 @@ TEST(SystemTest, CameraListCameras)
information.model_name = "Frozen Super";
information.firmware_version = "4.0.0";
information.definition_file_version = 1;
information.definition_file_uri =
"https://raw.githubusercontent.com/mavlink/MAVSDK/main/src/mavsdk/plugins/camera/e90_unit_test.xml";
information.definition_file_uri = "";
camera_server.set_information(information);

auto prom = std::promise<std::shared_ptr<System>>();
Expand All @@ -51,14 +50,13 @@ TEST(SystemTest, CameraListCameras)

bool found_camera = false;
camera.subscribe_camera_list([&](Camera::CameraList camera_list) {
LogWarn() << "got called";
if (!camera_list.cameras.empty()) {
found_camera = true;
}
});

// We have to wait until camera is found.
std::this_thread::sleep_for(std::chrono::milliseconds(100));
std::this_thread::sleep_for(std::chrono::milliseconds(1000));

EXPECT_EQ(camera.camera_list().cameras.size(), 1);
EXPECT_TRUE(found_camera);
Expand Down
17 changes: 15 additions & 2 deletions src/system_tests/camera_take_photo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,15 @@ TEST(SystemTest, CameraTakePhoto)
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;

Expand Down Expand Up @@ -54,8 +63,12 @@ TEST(SystemTest, CameraTakePhoto)

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);

// We want to take the picture in photo mode.
EXPECT_EQ(camera.set_mode(0, Camera::Mode::Photo), Camera::Result::Success);
EXPECT_EQ(camera.set_mode(1, Camera::Mode::Photo), Camera::Result::Success);

auto received_captured_info_prom = std::promise<void>{};
auto received_captured_info_fut = received_captured_info_prom.get_future();
Expand All @@ -68,7 +81,7 @@ TEST(SystemTest, CameraTakePhoto)
received_captured_info_prom.set_value();
});

EXPECT_EQ(camera.take_photo(0), Camera::Result::Success);
EXPECT_EQ(camera.take_photo(1), Camera::Result::Success);
ASSERT_EQ(
received_captured_info_fut.wait_for(std::chrono::seconds(10)), std::future_status::ready);
received_captured_info_fut.get();
Expand Down

0 comments on commit 0aeeb3d

Please sign in to comment.