Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mavros::std_plugins::FTPPlugin Class Reference

FTP plugin. More...

Inheritance diagram for mavros::std_plugins::FTPPlugin:
Inheritance graph
[legend]

Public Member Functions

 FTPPlugin ()
 
Subscriptions get_subscriptions () override
 Return vector of MAVLink message subscriptions (handlers) More...
 
void initialize (UAS &uas_) override
 Plugin initializer. More...
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Types

enum  OP {
  OP::IDLE, OP::ACK, OP::LIST, OP::OPEN,
  OP::READ, OP::WRITE, OP::CHECKSUM
}
 
typedef std::vector< uint8_t > V_FileData
 This type used in servicies to store 'data' fileds. More...
 

Private Member Functions

void add_dirent (const char *ptr, size_t slen)
 
bool checksum_cb (mavros_msgs::FileChecksum::Request &req, mavros_msgs::FileChecksum::Response &res)
 
void checksum_crc32_file (std::string &path)
 
bool close_cb (mavros_msgs::FileClose::Request &req, mavros_msgs::FileClose::Response &res)
 
bool close_file (std::string &path)
 
void create_directory (std::string &path)
 
void go_idle (bool is_error_, int r_errno_=0)
 Go to IDLE mode. More...
 
void handle_ack_checksum (FTPRequest &req)
 
void handle_ack_list (FTPRequest &req)
 
void handle_ack_open (FTPRequest &req)
 
void handle_ack_read (FTPRequest &req)
 
void handle_ack_write (FTPRequest &req)
 
void handle_file_transfer_protocol (const mavlink::mavlink_message_t *msg, FTPRequest &req)
 handler for mavlink::common::msg::FILE_TRANSFER_PROTOCOL More...
 
void handle_req_ack (FTPRequest &req)
 
void handle_req_nack (FTPRequest &req)
 
bool list_cb (mavros_msgs::FileList::Request &req, mavros_msgs::FileList::Response &res)
 
void list_directory (std::string &path)
 
void list_directory_end ()
 
bool mkdir_cb (mavros_msgs::FileMakeDir::Request &req, mavros_msgs::FileMakeDir::Response &res)
 
bool open_cb (mavros_msgs::FileOpen::Request &req, mavros_msgs::FileOpen::Response &res)
 
bool open_file (std::string &path, int mode)
 
bool read_cb (mavros_msgs::FileRead::Request &req, mavros_msgs::FileRead::Response &res)
 
bool read_file (std::string &path, size_t off, size_t len)
 
void read_file_end ()
 
bool remove_cb (mavros_msgs::FileRemove::Request &req, mavros_msgs::FileRemove::Response &res)
 
void remove_directory (std::string &path)
 
void remove_file (std::string &path)
 
bool rename_ (std::string &old_path, std::string &new_path)
 
bool rename_cb (mavros_msgs::FileRename::Request &req, mavros_msgs::FileRename::Response &res)
 
bool reset_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 Reset communication on both sides. More...
 
bool rmdir_cb (mavros_msgs::FileRemoveDir::Request &req, mavros_msgs::FileRemoveDir::Response &res)
 
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) More...
 
void send_calc_file_crc32_command (std::string &path)
 
void send_create_command ()
 
void send_create_dir_command (std::string &path)
 
void send_list_command ()
 
void send_open_ro_command ()
 
void send_open_wo_command ()
 
void send_read_command ()
 
void send_remove_command (std::string &path)
 
void send_remove_dir_command (std::string &path)
 
bool send_rename_command (std::string &old_path, std::string &new_path)
 
void send_reset ()
 
void send_terminate_command (uint32_t session)
 
void send_truncate_command (std::string &path, size_t length)
 
void send_write_command (const size_t bytes_to_copy)
 
bool truncate_cb (mavros_msgs::FileTruncate::Request &req, mavros_msgs::FileTruncate::Response &res)
 
void truncate_file (std::string &path, size_t length)
 
bool wait_completion (const int msecs)
 
size_t write_bytes_to_copy ()
 
bool write_cb (mavros_msgs::FileWrite::Request &req, mavros_msgs::FileWrite::Response &res)
 
bool write_file (std::string &path, size_t off, V_FileData &data)
 
void write_file_end ()
 

Static Private Member Functions

static constexpr int compute_rw_timeout (size_t len)
 

Private Attributes

uint32_t active_session
 session id of current operation More...
 
uint32_t checksum_crc32
 
ros::ServiceServer checksum_srv
 
ros::ServiceServer close_srv
 
std::condition_variable cond
 wait condvar More...
 
std::mutex cond_mutex
 
ros::NodeHandle ftp_nh
 
bool is_error
 error signaling flag (timeout/proto error) More...
 
uint16_t last_send_seqnr
 seqNumber for send. More...
 
std::vector< mavros_msgs::FileEntry > list_entries
 
uint32_t list_offset
 
std::string list_path
 
ros::ServiceServer list_srv
 
ros::ServiceServer mkdir_srv
 
OP op_state
 
std::string open_path
 
size_t open_size
 
ros::ServiceServer open_srv
 
int r_errno
 store errno from server More...
 
V_FileData read_buffer
 
uint32_t read_offset
 
size_t read_size
 
ros::ServiceServer read_srv
 
ros::ServiceServer remove_srv
 
ros::ServiceServer rename_srv
 
ros::ServiceServer reset_srv
 
ros::ServiceServer rmdir_srv
 
std::map< std::string, uint32_t > session_file_map
 
ros::ServiceServer truncate_srv
 
V_FileData write_buffer
 
V_FileData::iterator write_it
 
uint32_t write_offset
 
ros::ServiceServer write_srv
 

Static Private Attributes

static constexpr int CHUNK_TIMEOUT_MS = 200
 
static constexpr int LIST_TIMEOUT_MS = 5000
 
static constexpr size_t MAX_RESERVE_DIFF = 0x10000
 Maximum difference between allocated space and used. More...
 
static constexpr int OPEN_TIMEOUT_MS = 200
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
using ConstPtr = boost::shared_ptr< PluginBase const >
 
using HandlerCb = mavconn::MAVConnInterface::ReceivedCb
 generic message handler callback More...
 
using HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb >
 Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More...
 
using Ptr = boost::shared_ptr< PluginBase >
 
using Subscriptions = std::vector< HandlerInfo >
 Subscriptions vector. More...
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void capabilities_cb (UAS::MAV_CAP capabilities)
 
virtual void connection_cb (bool connected)
 
void enable_capabilities_cb ()
 
void enable_connection_cb ()
 
template<class _C >
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
template<class _C , class _T >
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 Plugin constructor Should not do anything before initialize() More...
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

FTP plugin.

Definition at line 197 of file ftp.cpp.


The documentation for this class was generated from the following file:


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 13 2023 02:17:50