Go to the documentation of this file.
19 #include <condition_variable>
22 #include <std_srvs/Empty.h>
23 #include <mavros_msgs/FileEntry.h>
24 #include <mavros_msgs/FileList.h>
25 #include <mavros_msgs/FileOpen.h>
26 #include <mavros_msgs/FileClose.h>
27 #include <mavros_msgs/FileRead.h>
28 #include <mavros_msgs/FileWrite.h>
29 #include <mavros_msgs/FileRemove.h>
30 #include <mavros_msgs/FileMakeDir.h>
31 #include <mavros_msgs/FileRemoveDir.h>
32 #include <mavros_msgs/FileTruncate.h>
33 #include <mavros_msgs/FileRename.h>
34 #include <mavros_msgs/FileChecksum.h>
40 namespace std_plugins {
48 class FTPRequest :
public mavlink::common::msg::FILE_TRANSFER_PROTOCOL {
107 return payload.data();
119 return reinterpret_cast<char *
>(
header()->
data);
123 return reinterpret_cast<uint32_t *
>(
header()->
data);
137 memcpy(
data_c(),
s.c_str(), sz);
143 return target_system;
153 ROS_DEBUG_NAMED(
"ftp",
"FTP:rm: SEQ(%u) SESS(%u) OPCODE(%u) RQOP(%u) SZ(%u) OFF(%u)",
154 hdr->seqNumber, hdr->session, hdr->opcode, hdr->req_opcode, hdr->size, hdr->offset);
157 return UAS_FCU(uas)->get_system_id() == target_system;
170 hdr->seqNumber = seqNumber;
174 ROS_DEBUG_NAMED(
"ftp",
"FTP:sm: SEQ(%u) SESS(%u) OPCODE(%u) SZ(%u) OFF(%u)",
175 hdr->seqNumber, hdr->session, hdr->opcode, hdr->size, hdr->offset);
178 UAS_FCU(uas)->send_message_ignore_drop(*
this);
182 mavlink::common::
msg::FILE_TRANSFER_PROTOCOL{}
186 mavlink::common::
msg::FILE_TRANSFER_PROTOCOL{}
217 PluginBase::initialize(uas_);
331 if (incoming_seqnr != expected_seqnr) {
333 incoming_seqnr, expected_seqnr);
401 ROS_ERROR_NAMED(
"ftp",
"FTP: NAK: %u Opcode: %u State: %u Errno: %d (%s)",
410 ROS_DEBUG_NAMED(
"ftp",
"FTP:m: ACK List SZ(%u) OFF(%u)", hdr->size, hdr->offset);
419 uint32_t n_list_entries = 0;
421 while (off < hdr->size) {
422 const char *ptr = req.
data_c() + off;
423 const size_t bytes_left = hdr->size - off;
425 size_t slen = strnlen(ptr, bytes_left);
432 else if (slen == bytes_left) {
453 if (hdr->size == 0) {
458 ROS_ASSERT_MSG(n_list_entries > 0,
"FTP:List don't parse entries");
473 ROS_INFO_NAMED(
"ftp",
"FTP:Open %s: success, session %u, size %zu",
500 const size_t bytes_to_copy = std::min<size_t>(bytes_left, hdr->size);
531 const size_t bytes_written = *req.
data_u32();
535 ROS_ASSERT_MSG(bytes_written <= bytes_left_before_advance,
"Bad write size");
539 std::advance(
write_it, bytes_written);
542 if (bytes_to_copy > 0) {
555 ROS_DEBUG_NAMED(
"ftp",
"FTP:m: ACK CalcFileCRC32 OPCODE(%u)", hdr->req_opcode);
571 void go_idle(
bool is_error_,
int r_errno_ = 0)
656 std::ostringstream os;
661 std::string paths = os.str();
663 ROS_ERROR_NAMED(
"ftp",
"FTP: rename file paths is too long: %zu", paths.size());
692 mavros_msgs::FileEntry ent;
696 ent.name.assign(ptr + 1, slen - 1);
697 ent.type = mavros_msgs::FileEntry::TYPE_DIRECTORY;
703 std::string name_size(ptr + 1, slen - 1);
705 auto sep_it = std::find(name_size.begin(), name_size.end(),
'\t');
706 ent.name.assign(name_size.begin(), sep_it);
707 ent.type = mavros_msgs::FileEntry::TYPE_FILE;
709 if (sep_it != name_size.end()) {
710 name_size.erase(name_size.begin(), sep_it + 1);
711 if (name_size.size() != 0)
712 ent.size = std::stoi(name_size);
742 if (mode == mavros_msgs::FileOpenRequest::MODE_READ)
744 else if (mode == mavros_msgs::FileOpenRequest::MODE_WRITE)
746 else if (mode == mavros_msgs::FileOpenRequest::MODE_CREATE)
831 bool rename_(std::string &old_path, std::string &new_path) {
868 std::unique_lock<std::mutex> lock(
cond_mutex);
870 bool is_timedout =
cond.wait_for(lock, std::chrono::milliseconds(msecs))
871 == std::cv_status::timeout;
889 #define SERVICE_IDLE_CHECK() \
890 if (op_state != OP::IDLE) { \
891 ROS_ERROR_NAMED("ftp", "FTP: Busy"); \
895 bool list_cb(mavros_msgs::FileList::Request &req,
896 mavros_msgs::FileList::Response &res)
911 bool open_cb(mavros_msgs::FileOpen::Request &req,
912 mavros_msgs::FileOpen::Response &res)
920 req.file_path.c_str());
924 res.success =
open_file(req.file_path, req.mode);
934 bool close_cb(mavros_msgs::FileClose::Request &req,
935 mavros_msgs::FileClose::Response &res)
948 bool read_cb(mavros_msgs::FileRead::Request &req,
949 mavros_msgs::FileRead::Response &res)
953 res.success =
read_file(req.file_path, req.offset, req.size);
965 bool write_cb(mavros_msgs::FileWrite::Request &req,
966 mavros_msgs::FileWrite::Response &res)
970 const size_t data_size = req.data.size();
971 res.success =
write_file(req.file_path, req.offset, req.data);
982 mavros_msgs::FileRemove::Response &res)
994 mavros_msgs::FileRename::Response &res)
998 res.success =
rename_(req.old_path, req.new_path);
1009 mavros_msgs::FileTruncate::Response &res)
1022 mavros_msgs::FileMakeDir::Response &res)
1033 bool rmdir_cb(mavros_msgs::FileRemoveDir::Request &req,
1034 mavros_msgs::FileRemoveDir::Response &res)
1046 mavros_msgs::FileChecksum::Response &res)
1058 #undef SERVICE_IDLE_CHECK
1065 std_srvs::Empty::Response &res)
@ kCmdBurstReadFile
Burst download session file.
uint32_t active_session
session id of current operation
void handle_ack_checksum(FTPRequest &req)
static const uint8_t DATA_MAXSZ
payload.size() - header bytes
bool write_file(std::string &path, size_t off, V_FileData &data)
@ kErrFailErrno
Command failed, errno sent back in PayloadHeader.data[1].
@ kCmdListDirectory
List files in <path> from <offset>
void list_directory(std::string &path)
@ kErrFailFileExists
File exists already.
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
void send_terminate_command(uint32_t session)
@ kCmdCalcFileCRC32
Calculate CRC32 for file at <path>
std::condition_variable cond
wait condvar
void go_idle(bool is_error_, int r_errno_=0)
Go to IDLE mode.
static const char DIRENT_FILE
void set_data_string(std::string &s)
Copy string to payload.
ros::ServiceServer reset_srv
ros::ServiceServer write_srv
@ kErrInvalidDataSize
PayloadHeader.size is invalid.
@ kCmdTruncateFile
Truncate file at <path> to <offset> length.
int r_errno
store errno from server
ros::ServiceServer truncate_srv
void send_calc_file_crc32_command(std::string &path)
#define ROS_DEBUG_STREAM_NAMED(name, args)
PluginBase()
Plugin constructor Should not do anything before initialize()
@ kCmdCreateDirectory
Creates directory at <path>
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
bool list_cb(mavros_msgs::FileList::Request &req, mavros_msgs::FileList::Response &res)
@ kErrNoSessionsAvailable
All available Sessions in use.
FTPRequest(Opcode op, uint8_t session=0)
bool rmdir_cb(mavros_msgs::FileRemoveDir::Request &req, mavros_msgs::FileRemoveDir::Response &res)
std::recursive_mutex mutex
bool close_cb(mavros_msgs::FileClose::Request &req, mavros_msgs::FileClose::Response &res)
bool send_rename_command(std::string &old_path, std::string &new_path)
bool is_error
error signaling flag (timeout/proto error)
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
std::map< std::string, uint32_t > session_file_map
std::vector< uint8_t > V_FileData
This type used in servicies to store 'data' fileds.
bool truncate_cb(mavros_msgs::FileTruncate::Request &req, mavros_msgs::FileTruncate::Response &res)
uint8_t get_tgt_component()
Return communication target component.
#define ROS_ERROR_NAMED(name,...)
void send_any_path_command(FTPRequest::Opcode op, const std::string &debug_msg, std::string &path, uint32_t offset)
Send any command with string payload (usually file/dir path)
bool wait_completion(const int msecs)
@ kCmdCreateFile
Creates file at <path> for writing, returns <session>
ros::ServiceServer list_srv
ros::ServiceServer checksum_srv
uint32_t offset
Offsets for List and Read commands.
bool read_file(std::string &path, size_t off, size_t len)
ErrorCode
Error codes returned in Nak response.
bool open_cb(mavros_msgs::FileOpen::Request &req, mavros_msgs::FileOpen::Response &res)
bool write_cb(mavros_msgs::FileWrite::Request &req, mavros_msgs::FileWrite::Response &res)
void send_remove_command(std::string &path)
void remove_file(std::string &path)
bool rename_cb(mavros_msgs::FileRename::Request &req, mavros_msgs::FileRename::Response &res)
@ kErrFailFileProtected
File is write protected.
@ kCmdWriteFile
Writes <size> bytes to <offset> in <session>
size_t write_bytes_to_copy()
ros::ServiceServer close_srv
void remove_directory(std::string &path)
void send_truncate_command(std::string &path, size_t length)
void truncate_file(std::string &path, size_t length)
bool read_cb(mavros_msgs::FileRead::Request &req, mavros_msgs::FileRead::Response &res)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool mkdir_cb(mavros_msgs::FileMakeDir::Request &req, mavros_msgs::FileMakeDir::Response &res)
void handle_req_nack(FTPRequest &req)
#define ROS_INFO_NAMED(name,...)
static const char DIRENT_SKIP
static constexpr int OPEN_TIMEOUT_MS
@ kErrInvalidSession
Session is not currently open.
ros::ServiceServer read_srv
#define ROS_DEBUG_NAMED(name,...)
uint8_t req_opcode
Request opcode returned in kRspAck, kRspNak message.
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void initialize(UAS &uas_) override
Plugin initializer.
void handle_ack_read(FTPRequest &req)
static constexpr int CHUNK_TIMEOUT_MS
void handle_ack_list(FTPRequest &req)
bool remove_cb(mavros_msgs::FileRemove::Request &req, mavros_msgs::FileRemove::Response &res)
static constexpr int compute_rw_timeout(size_t len)
@ kErrEOF
Offset past end of file for List and Read commands.
@ kErrFail
Unknown failure.
void create_directory(std::string &path)
uint8_t size
Size of data.
@ kCmdTerminateSession
Terminates open Read session.
#define ROS_ASSERT_MSG(cond,...)
static constexpr size_t MAX_RESERVE_DIFF
Maximum difference between allocated space and used.
std::vector< mavros_msgs::FileEntry > list_entries
@ kCmdOpenFileRO
Opens file at <path> for reading, returns <session>
void send_open_ro_command()
@ kCmdNone
ignored, always acked
@ kCmdRemoveFile
Remove file at <path>
bool decode_valid(UAS *uas)
Decode and check target system.
uint8_t padding[2]
32 bit aligment padding
void handle_ack_open(FTPRequest &req)
void checksum_crc32_file(std::string &path)
@ kCmdOpenFileWO
Opens file at <path> for writing, returns <session>
V_FileData::iterator write_it
uint8_t get_target_system_id()
void list_directory_end()
FTP Request message abstraction class.
static const char DIRENT_DIR
@ kCmdReadFile
Reads <size> bytes from <offset> in <session>
void send_remove_dir_command(std::string &path)
void add_dirent(const char *ptr, size_t slen)
uint8_t get_tgt_system()
Return communication target system.
bool checksum_cb(mavros_msgs::FileChecksum::Request &req, mavros_msgs::FileChecksum::Response &res)
uint8_t opcode
Command opcode.
@ kErrUnknownCommand
Unknown command opcode.
bool open_file(std::string &path, int mode)
MAVROS Plugin base class.
uint8_t data[]
command data, varies by Opcode
static constexpr int LIST_TIMEOUT_MS
void send_open_wo_command()
@ kCmdResetSessions
Terminates all open Read sessions.
#define ROS_WARN_NAMED(name,...)
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
void send_write_command(const size_t bytes_to_copy)
ros::ServiceServer open_srv
void handle_file_transfer_protocol(const mavlink::mavlink_message_t *msg, FTPRequest &req)
handler for mavlink::common::msg::FILE_TRANSFER_PROTOCOL
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
void handle_req_ack(FTPRequest &req)
uint16_t seqNumber
sequence number for message
uint8_t session
Session id for read and write commands.
ros::ServiceServer rmdir_srv
void send_create_dir_command(std::string &path)
uint16_t last_send_seqnr
seqNumber for send.
constexpr std::underlying_type< _T >::type enum_value(_T e)
@ kCmdRename
Rename <path1> to <path2>
ros::ServiceServer mkdir_srv
#define SERVICE_IDLE_CHECK()
void send_create_command()
ros::ServiceServer remove_srv
@ kCmdRemoveDirectory
Removes Directory at <path>, must be empty.
void handle_ack_write(FTPRequest &req)
ros::ServiceServer rename_srv
bool reset_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Reset communication on both sides.
bool close_file(std::string &path)
bool rename_(std::string &old_path, std::string &new_path)
void send(UAS *uas, uint16_t seqNumber)
Encode and send message.
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03