Skip to content

Commit

Permalink
camera wip
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 12, 2024
1 parent be3d792 commit e6e3a71
Show file tree
Hide file tree
Showing 8 changed files with 65 additions and 70 deletions.
1 change: 1 addition & 0 deletions src/mavsdk/core/mavlink_ftp_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -377,6 +377,7 @@ void MavlinkFtpClient::process_mavlink_ftp_message(const mavlink_message_t& msg)
bool MavlinkFtpClient::download_start(Work& work, DownloadItem& item)
{
fs::path local_path = fs::path(item.local_folder) / fs::path(item.remote_path).filename();
fs::create_directories(fs::path(item.local_folder));

if (_debugging) {
LogDebug() << "Trying to open write to local path: " << local_path.string();
Expand Down
10 changes: 7 additions & 3 deletions src/mavsdk/core/mavlink_ftp_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,7 @@ MavlinkFtpServer::_path_from_string(const std::string& payload_path)

// No permission whatsoever if the root dir is not set.
if (_root_dir.empty()) {
LogWarn() << "Root dir not set!";
return ServerResult::ERR_FAIL;
}

Expand Down Expand Up @@ -281,10 +282,13 @@ void MavlinkFtpServer::set_root_directory(const std::string& root_dir)
{
std::lock_guard<std::mutex> lock(_mutex);

std::error_code ignored;
_root_dir = fs::canonical(fs::path(root_dir), ignored).string();
std::error_code ec;
_root_dir = fs::canonical(fs::path(root_dir), ec).string();
if (ec) {
LogWarn() << "Root dir could not be made absolute: " << ec.message();
}
if (_debugging) {
LogDebug() << "Set root dir to: " << _root_dir;
LogDebug() << "Set root dir to: " << _root_dir << " from: " << root_dir;
}
}

Expand Down
1 change: 0 additions & 1 deletion src/mavsdk/core/param_value.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -588,7 +588,6 @@ std::array<char, 128> ParamValue::get_128_bytes() const

bool ParamValue::operator==(const std::string& value_str) const
{
// LogDebug() << "Compare " << value_str() << " and " << rhs.value_str();
if (std::get_if<uint8_t>(&_value)) {
return std::get<uint8_t>(_value) == std::stoi(value_str);
} else if (std::get_if<int8_t>(&_value)) {
Expand Down
6 changes: 3 additions & 3 deletions src/mavsdk/plugins/camera/camera_definition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ bool CameraDefinition::parse_xml()
} else {
auto maybe_range_options = parse_range_options(e_parameter, param_name, type_map);
if (!std::get<0>(maybe_range_options)) {
LogWarn() << "Not found: " << param_name;
LogWarn() << "Range not found for: " << param_name;
continue;
}

Expand Down Expand Up @@ -363,7 +363,7 @@ CameraDefinition::parse_range_options(

const char* min_str = param_handle->Attribute("min");
if (!min_str) {
LogErr() << "min range missing for " << param_name;
LogDebug() << "min range missing for " << param_name;
return std::make_tuple<>(false, options, default_option);
}

Expand All @@ -372,7 +372,7 @@ CameraDefinition::parse_range_options(

const char* max_str = param_handle->Attribute("max");
if (!max_str) {
LogErr() << "max range missing for " << param_name;
LogDebug() << "max range missing for " << param_name;
return std::make_tuple<>(false, options, default_option);
}

Expand Down
57 changes: 33 additions & 24 deletions src/mavsdk/plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1324,7 +1324,6 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca

} else {
potential_camera.is_fetching_camera_definition = true;
auto download_path = _tmp_download_path / file_cache_tag;

if (starts_with(url, "http://") || starts_with(url, "https://")) {
#if BUILD_WITHOUT_CURL == 1
Expand All @@ -1338,6 +1337,8 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca

auto camera_id = camera_id_for_potential_camera_with_lock(potential_camera);

auto download_path = _tmp_download_path / file_cache_tag;

_http_loader->download_async(
url,
download_path,
Expand Down Expand Up @@ -1372,7 +1373,6 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
}
load_camera_definition_with_lock(*maybe_potential_camera, download_path);
maybe_potential_camera->is_fetching_camera_definition = false;
// TODO: add parsing result
maybe_potential_camera->camera_definition_result = Camera::Result::Success;
notify_camera_list();
}
Expand All @@ -1383,30 +1383,29 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca

auto camera_id = camera_id_for_potential_camera_with_lock(potential_camera);

auto downloaded_filename = strip_prefix(strip_prefix(url, "mavlinkftp://"), "mftp://");

_system_impl->mavlink_ftp_client().download_async(
strip_prefix(strip_prefix(url, "mavlinkftp://"), "mftp://"),
download_path,
downloaded_filename,
_tmp_download_path,
false,
[file_cache_tag, download_path, camera_id, this](
[file_cache_tag, downloaded_filename, camera_id, this](
MavlinkFtpClient::ClientResult client_result,
MavlinkFtpClient::ProgressData progress_data) mutable {
// TODO: check if we still exist
if (client_result == MavlinkFtpClient::ClientResult::Success ||
client_result == MavlinkFtpClient::ClientResult::Next) {
if (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;
}
return;
}

std::lock_guard lock(_mutex);
auto maybe_potential_camera =
maybe_potential_camera_for_camera_id_with_lock(camera_id);
if (maybe_potential_camera != nullptr) {
LogErr() << "Failed to find camera.";
if (maybe_potential_camera == nullptr) {
LogErr() << "Failed to find camera with ID " << camera_id;
return;
}

Expand All @@ -1418,15 +1417,17 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca
return;
}

LogDebug() << "File download finished to " << download_path;
auto downloaded_filepath = _tmp_download_path / downloaded_filename;

LogDebug() << "File download finished to " << downloaded_filepath;
if (_file_cache) {
// Cache the file (this will move/remove the temp file as well)
download_path = _file_cache->insert(file_cache_tag, download_path)
.value_or(download_path);
LogDebug() << "Cached path: " << download_path;
downloaded_filepath =
_file_cache->insert(file_cache_tag, downloaded_filepath)
.value_or(downloaded_filepath);
LogDebug() << "Cached path: " << downloaded_filepath;
}
load_camera_definition_with_lock(*maybe_potential_camera, download_path);
// TODO: add parsing result
load_camera_definition_with_lock(*maybe_potential_camera, downloaded_filepath);
maybe_potential_camera->is_fetching_camera_definition = false;
maybe_potential_camera->camera_definition_result = Camera::Result::Success;
notify_camera_list();
Expand All @@ -1446,7 +1447,16 @@ void CameraImpl::load_camera_definition_with_lock(
potential_camera.camera_definition = std::make_unique<CameraDefinition>();
}

potential_camera.camera_definition->load_file(path.string());
if (!potential_camera.camera_definition->load_file(path.string())) {
LogErr() << "Failed to load camera definition: " << path;
// We can't keep something around that's not loaded correctly.
potential_camera.camera_definition = nullptr;
return;
}

// We assume default settings initially and then load the params one by one.
// This way we can start using it straightaway.
potential_camera.camera_definition->assume_default_settings();
}

void CameraImpl::process_video_information(const mavlink_message_t& message)
Expand Down Expand Up @@ -1587,10 +1597,8 @@ bool CameraImpl::get_possible_options_with_lock(
}

for (const auto& value : values) {
std::stringstream ss{};
ss << value;
Camera::Option option{};
option.option_id = ss.str();
option.option_id = value.get_string();
if (!camera.camera_definition->is_setting_range(setting_id)) {
get_option_str_with_lock(
camera, setting_id, option.option_id, option.option_description);
Expand Down Expand Up @@ -2001,7 +2009,7 @@ CameraImpl::get_possible_setting_options(int32_t camera_id)
}

auto& camera = *maybe_potential_camera;
if (!camera.is_fetching_camera_definition) {
if (camera.is_fetching_camera_definition) {
result.first = Camera::Result::SettingsLoading;
return result;
}
Expand Down Expand Up @@ -2037,6 +2045,7 @@ CameraImpl::get_possible_setting_options_with_lock(PotentialCamera& potential_ca
result.second.push_back(setting_options);
}

result.first = Camera::Result::Success;
return result;
}

Expand Down Expand Up @@ -2355,7 +2364,7 @@ CameraImpl::get_current_settings(int32_t camera_id)
}

auto& camera = *maybe_potential_camera;
if (!camera.is_fetching_camera_definition) {
if (camera.is_fetching_camera_definition) {
result.first = Camera::Result::SettingsLoading;
return result;
}
Expand Down
36 changes: 3 additions & 33 deletions src/mavsdk/plugins/camera/e90_unit_test.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8" ?>
<mavlinkcamera>
<definition version="15">
<definition version="16">
<model>E90</model>
<vendor>Yuneec</vendor>
</definition>
Expand Down Expand Up @@ -61,7 +61,7 @@
<option name="Lock" value="99" />
</options>
</parameter>
<parameter name="CAM_CUSTOMWB" type="uint16" min="3000" max="8000" default="5500" control="0">
<parameter name="CAM_CUSTOMWB" type="uint16" min="3000" max="8000" default="5500" control="0" step="1">
<description>Custom White Balance (K)</description>
</parameter>
<parameter name="CAM_EXPMODE" type="uint32" default="0">
Expand Down Expand Up @@ -914,39 +914,9 @@
<option name="PAL" value="1" />
</options>
</parameter>
<!--
Spot Metering Area
Encoded as 2 uint8 values
x = (value >> 8) & 0xFF
y = value & 0xFF
x is x_coord / screen_witdh * 100
y is y_coord / screen_height * 100
-->
<parameter name="CAM_SPOTAREA" type="uint16" control="0" default="0">
<description>Spot Metering Area</description>
</parameter>
<!--
Video stream aspect ratio
Float value is width / height (i.e. 3:2 = 1.5)
-->
<parameter name="CAM_ASPECTRATIO" type="float" control="0" readonly="1" default="01.777777">
<parameter name="CAM_ASPECTRATIO" type="float" control="0" readonly="1" default="1.78" min="1.33" max="1.78" step="0.01">
<description>Video Stream Aspect Ratio</description>
</parameter>
<parameter name="CAM_WIFIPASSWD" type="string" control="0" writeonly="1" default="">
<description>Set WiFi Password</description>
</parameter>
<parameter name="CAM_SYSTEMTIME" type="uint64" control="0" writeonly="1">
<description>Set System Time</description>
</parameter>
<!--
These parameters are not used by DataPilot
-->
<parameter name="CAM_PHOTOMODE" type="custom" control="0">
<description>Camera Photo Mode</description>
</parameter>
<parameter name="CAM_FWBUNDLEVER" type="custom" control="0" readonly="1">
<description>Firmware Bundle Version</description>
</parameter>
</parameters>
<localization>
<!-- If no appropriate locale is found, the original (above) will be used -->
Expand Down
20 changes: 16 additions & 4 deletions src/system_tests/camera_definition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@ using namespace mavsdk;

TEST(SystemTest, CameraDefinition)
{
Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};
Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}};

Mavsdk mavsdk_camera{Mavsdk::Configuration{Mavsdk::ComponentType::Camera}};
Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}};

ASSERT_EQ(
mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"),
Expand All @@ -24,15 +24,15 @@ TEST(SystemTest, CameraDefinition)

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

EXPECT_EQ(ftp_server.set_root_dir("src/plugins/camera/"), FtpServer::Result::Success);
EXPECT_EQ(ftp_server.set_root_dir("src/mavsdk/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_version = 16;
information.definition_file_uri = "mavlinkftp://e90_unit_test.xml";
EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success);

Expand All @@ -54,4 +54,16 @@ TEST(SystemTest, CameraDefinition)
auto camera = Camera{system};

std::this_thread::sleep_for(std::chrono::seconds(5));
EXPECT_EQ(camera.camera_list().cameras.size(), 1);
auto possible_setting_options = camera.get_possible_setting_options(1);
ASSERT_EQ(possible_setting_options.first, Camera::Result::Success);

for (auto setting_option : possible_setting_options.second) {
std::cout << setting_option.setting_id << "->" << setting_option.setting_description
<< std::endl;
for (auto option : setting_option.options) {
std::cout << "Option: " << option.option_id << "->" << option.option_description
<< std::endl;
}
}
}
4 changes: 2 additions & 2 deletions src/system_tests/camera_list_cameras.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,9 @@ using namespace mavsdk;

TEST(SystemTest, CameraListCameras)
{
Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}};
Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}};

Mavsdk mavsdk_camera{Mavsdk::Configuration{Mavsdk::ComponentType::Camera}};
Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}};

ASSERT_EQ(
mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"),
Expand Down

0 comments on commit e6e3a71

Please sign in to comment.