Skip to content

Commit

Permalink
Merge pull request #2331 from mavlink/pr-ftp-list-dir-api
Browse files Browse the repository at this point in the history
ftp: split list_directory response
  • Loading branch information
julianoes committed Jul 15, 2024
2 parents 68dfe6b + 2607261 commit a7f7353
Show file tree
Hide file tree
Showing 13 changed files with 1,187 additions and 418 deletions.
33 changes: 16 additions & 17 deletions examples/ftp_client/ftp_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,22 +70,16 @@ Ftp::Result remove_file(Ftp& ftp, const std::string& path)
Ftp::Result remove_directory(Ftp& ftp, const std::string& path, bool recursive = true)
{
if (recursive) {
auto prom = std::promise<std::pair<Ftp::Result, std::vector<std::string>>>{};
auto prom = std::promise<std::pair<Ftp::Result, Ftp::ListDirectoryData>>{};
auto future_result = prom.get_future();
ftp.list_directory_async(path, [&prom](Ftp::Result result, std::vector<std::string> list) {
prom.set_value(std::pair<Ftp::Result, std::vector<std::string>>(result, list));
ftp.list_directory_async(path, [&prom](Ftp::Result result, auto data) {
prom.set_value(std::pair(result, data));
});

std::pair<Ftp::Result, std::vector<std::string>> result = future_result.get();
auto result = future_result.get();
if (result.first == Ftp::Result::Success) {
for (auto entry : result.second) {
if (entry[0] == 'D') {
remove_directory(ftp, path + "/" + entry.substr(1, entry.size() - 1));
} else if (entry[0] == 'F') {
auto i = entry.find('\t');
std::string name = entry.substr(1, i - 1);
remove_file(ftp, path + "/" + name);
}
for (auto entry : result.second.dirs) {
remove_directory(ftp, path + "/" + entry.substr(1, entry.size() - 1));
}
}
}
Expand All @@ -101,15 +95,20 @@ Ftp::Result remove_directory(Ftp& ftp, const std::string& path, bool recursive =
Ftp::Result list_directory(Ftp& ftp, const std::string& path)
{
std::cerr << "List directory: " << path << '\n';
auto prom = std::promise<std::pair<Ftp::Result, std::vector<std::string>>>{};
auto prom = std::promise<std::pair<Ftp::Result, Ftp::ListDirectoryData>>{};
auto future_result = prom.get_future();
ftp.list_directory_async(path, [&prom](Ftp::Result result, std::vector<std::string> list) {
prom.set_value(std::pair<Ftp::Result, std::vector<std::string>>(result, list));
ftp.list_directory_async(path, [&prom](Ftp::Result result, Ftp::ListDirectoryData data) {
prom.set_value(std::pair(result, data));
});

std::pair<Ftp::Result, std::vector<std::string>> result = future_result.get();
auto result = future_result.get();
if (result.first == Ftp::Result::Success) {
for (auto entry : result.second) {
std::cerr << "Directories: " << '\n';
for (auto entry : result.second.dirs) {
std::cerr << entry << '\n';
}
std::cerr << "Files: " << '\n';
for (auto entry : result.second.files) {
std::cerr << entry << '\n';
}
}
Expand Down
2 changes: 1 addition & 1 deletion proto
Submodule proto updated 1 files
+7 −1 protos/ftp/ftp.proto
142 changes: 66 additions & 76 deletions src/mavsdk/core/mavlink_ftp_client.cpp

Large diffs are not rendered by default.

11 changes: 3 additions & 8 deletions src/mavsdk/core/mavlink_ftp_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ class MavlinkFtpClient {
using ResultCallback = std::function<void(ClientResult)>;
using UploadCallback = std::function<void(ClientResult, ProgressData)>;
using DownloadCallback = std::function<void(ClientResult, ProgressData)>;
using ListDirectoryCallback = std::function<void(ClientResult, std::vector<std::string>)>;
using ListDirectoryCallback =
std::function<void(ClientResult, std::vector<std::string>, std::vector<std::string>)>;
using AreFilesIdenticalCallback = std::function<void(ClientResult, bool)>;

void do_work();
Expand Down Expand Up @@ -206,6 +207,7 @@ class MavlinkFtpClient {
ListDirectoryCallback callback{};
uint32_t offset{0};
std::vector<std::string> dirs{};
std::vector<std::string> files{};
};

using Item = std::variant<
Expand Down Expand Up @@ -299,13 +301,6 @@ class MavlinkFtpClient {

void terminate_session(Work& work);

template<typename CallbackT> void call_callback(const CallbackT& callback, ClientResult result);
template<typename CallbackT>
void call_callback(
const CallbackT& callback,
ClientResult result,
const typename CallbackT::second_argument_type& extra_arg);

static ClientResult result_from_nak(PayloadHeader* payload);

void timeout();
Expand Down
68 changes: 40 additions & 28 deletions src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,35 +240,47 @@ void ComponentMetadataImpl::retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE

const std::filesystem::path local_path =
tmp_download_path / std::filesystem::path(download_path).filename();
_system_impl->mavlink_ftp_client().download_async(
download_path,
tmp_download_path.string(),
true,
[this, &component, local_path, compid, type, file_cache_tag](
MavlinkFtpClient::ClientResult download_result,
MavlinkFtpClient::ProgressData progress_data) {
if (download_result == MavlinkFtpClient::ClientResult::Next) {
if (_verbose_debugging) {
LogDebug()
<< "File download progress: " << progress_data.bytes_transferred
<< '/' << progress_data.total_bytes;
}
// TODO: detect slow link (e.g. telemetry), and cancel download
// (fallback to http) e.g. by estimating the remaining download time,
// and cancel if >40s
} else {
if (_verbose_debugging) {
LogDebug() << "File download ended with result " << download_result;
}
if (download_result == MavlinkFtpClient::ClientResult::Success) {
component.current_metadata_path() =
extract_and_cache_file(local_path, file_cache_tag);

_system_impl->call_user_callback([this,
download_path,
tmp_download_path,
&component,
target_compid,
local_path,
compid,
type,
file_cache_tag]() {
_system_impl->mavlink_ftp_client().download_async(
download_path,
tmp_download_path.string(),
true,
[this, &component, local_path, compid, type, file_cache_tag](
MavlinkFtpClient::ClientResult download_result,
MavlinkFtpClient::ProgressData progress_data) {
if (download_result == MavlinkFtpClient::ClientResult::Next) {
if (_verbose_debugging) {
LogDebug() << "File download progress: "
<< progress_data.bytes_transferred << '/'
<< progress_data.total_bytes;
}
// TODO: detect slow link (e.g. telemetry), and cancel download
// (fallback to http) e.g. by estimating the remaining download
// time, and cancel if >40s
} else {
if (_verbose_debugging) {
LogDebug()
<< "File download ended with result " << download_result;
}
if (download_result == MavlinkFtpClient::ClientResult::Success) {
component.current_metadata_path() =
extract_and_cache_file(local_path, file_cache_tag);
}
// Move on to the next uri or type
retrieve_metadata(compid, type);
}
// Move on to the next uri or type
retrieve_metadata(compid, type);
}
},
target_compid);
},
target_compid);
});

} else {
// http(s) download
Expand Down
26 changes: 25 additions & 1 deletion src/mavsdk/plugins/ftp/ftp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

namespace mavsdk {

using ListDirectoryData = Ftp::ListDirectoryData;
using ProgressData = Ftp::ProgressData;

Ftp::Ftp(System& system) : PluginBase(), _impl{std::make_unique<FtpImpl>(system)} {}
Expand Down Expand Up @@ -37,7 +38,7 @@ void Ftp::list_directory_async(std::string remote_dir, const ListDirectoryCallba
_impl->list_directory_async(remote_dir, callback);
}

std::pair<Ftp::Result, std::vector<std::string>> Ftp::list_directory(std::string remote_dir) const
std::pair<Ftp::Result, Ftp::ListDirectoryData> Ftp::list_directory(std::string remote_dir) const
{
return _impl->list_directory(remote_dir);
}
Expand Down Expand Up @@ -102,6 +103,29 @@ Ftp::Result Ftp::set_target_compid(uint32_t compid) const
return _impl->set_target_compid(compid);
}

bool operator==(const Ftp::ListDirectoryData& lhs, const Ftp::ListDirectoryData& rhs)
{
return (rhs.dirs == lhs.dirs) && (rhs.files == lhs.files);
}

std::ostream& operator<<(std::ostream& str, Ftp::ListDirectoryData const& list_directory_data)
{
str << std::setprecision(15);
str << "list_directory_data:" << '\n' << "{\n";
str << " dirs: [";
for (auto it = list_directory_data.dirs.begin(); it != list_directory_data.dirs.end(); ++it) {
str << *it;
str << (it + 1 != list_directory_data.dirs.end() ? ", " : "]\n");
}
str << " files: [";
for (auto it = list_directory_data.files.begin(); it != list_directory_data.files.end(); ++it) {
str << *it;
str << (it + 1 != list_directory_data.files.end() ? ", " : "]\n");
}
str << '}';
return str;
}

bool operator==(const Ftp::ProgressData& lhs, const Ftp::ProgressData& rhs)
{
return (rhs.bytes_transferred == lhs.bytes_transferred) && (rhs.total_bytes == lhs.total_bytes);
Expand Down
20 changes: 13 additions & 7 deletions src/mavsdk/plugins/ftp/ftp_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,24 +74,30 @@ void FtpImpl::upload_async(
});
}

std::pair<Ftp::Result, std::vector<std::string>> FtpImpl::list_directory(const std::string& path)
std::pair<Ftp::Result, Ftp::ListDirectoryData> FtpImpl::list_directory(const std::string& path)
{
std::promise<std::pair<Ftp::Result, std::vector<std::string>>> prom;
std::promise<std::pair<Ftp::Result, Ftp::ListDirectoryData>> prom;
auto fut = prom.get_future();

list_directory_async(path, [&](Ftp::Result result, std::vector<std::string> list) {
prom.set_value(std::pair<Ftp::Result, std::vector<std::string>>{result, list});
list_directory_async(path, [&](Ftp::Result result, Ftp::ListDirectoryData data) {
prom.set_value(std::pair<Ftp::Result, Ftp::ListDirectoryData>(result, data));
});
return fut.get();
}

void FtpImpl::list_directory_async(const std::string& path, Ftp::ListDirectoryCallback callback)
{
_system_impl->mavlink_ftp_client().list_directory_async(
path, [callback, this](MavlinkFtpClient::ClientResult result, auto&& dirs) {
path,
[callback, this](
MavlinkFtpClient::ClientResult result,
std::vector<std::string> dirs,
std::vector<std::string> files) {
if (callback) {
_system_impl->call_user_callback([temp_callback = callback, result, dirs, this]() {
temp_callback(result_from_mavlink_ftp_result(result), dirs);
_system_impl->call_user_callback([=]() {
callback(
result_from_mavlink_ftp_result(result),
Ftp::ListDirectoryData{dirs, files});
});
}
});
Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/plugins/ftp/ftp_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class FtpImpl : public PluginImplBase {
void enable() override;
void disable() override;

std::pair<Ftp::Result, std::vector<std::string>> list_directory(const std::string& path);
std::pair<Ftp::Result, Ftp::ListDirectoryData> list_directory(const std::string& path);
Ftp::Result create_directory(const std::string& path);
Ftp::Result remove_directory(const std::string& path);
Ftp::Result remove_file(const std::string& path);
Expand Down
27 changes: 25 additions & 2 deletions src/mavsdk/plugins/ftp/include/plugins/ftp/ftp.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,29 @@ class Ftp : public PluginBase {
*/
~Ftp() override;

/**
* @brief
*/
struct ListDirectoryData {
std::vector<std::string> dirs{}; /**< @brief The found directories. */
std::vector<std::string> files{}; /**< @brief The found files. */
};

/**
* @brief Equal operator to compare two `Ftp::ListDirectoryData` objects.
*
* @return `true` if items are equal.
*/
friend bool operator==(const Ftp::ListDirectoryData& lhs, const Ftp::ListDirectoryData& rhs);

/**
* @brief Stream operator to print information about a `Ftp::ListDirectoryData`.
*
* @return A reference to the stream.
*/
friend std::ostream&
operator<<(std::ostream& str, Ftp::ListDirectoryData const& list_directory_data);

/**
* @brief Progress data type for file transfer.
*/
Expand Down Expand Up @@ -139,7 +162,7 @@ class Ftp : public PluginBase {
/**
* @brief Callback type for list_directory_async.
*/
using ListDirectoryCallback = std::function<void(Result, std::vector<std::string>)>;
using ListDirectoryCallback = std::function<void(Result, ListDirectoryData)>;

/**
* @brief Lists items from a remote directory.
Expand All @@ -155,7 +178,7 @@ class Ftp : public PluginBase {
*
* @return Result of request.
*/
std::pair<Result, std::vector<std::string>> list_directory(std::string remote_dir) const;
std::pair<Result, Ftp::ListDirectoryData> list_directory(std::string remote_dir) const;

/**
* @brief Creates a remote directory.
Expand Down
Loading

0 comments on commit a7f7353

Please sign in to comment.