PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_ftp.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 /// @file mavlink_ftp.h
37 /// @author px4dev, Don Gagne <don@thegagnes.com>
38 
39 #include <dirent.h>
40 #include <queue.h>
41 
42 #include <px4_platform_common/defines.h>
43 #include <systemlib/err.h>
44 #include <drivers/drv_hrt.h>
45 
46 #include "mavlink_bridge_header.h"
47 
48 class MavlinkFtpTest;
49 class Mavlink;
50 
51 /// MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL message.
53 {
54 public:
55  MavlinkFTP(Mavlink *mavlink);
56  ~MavlinkFTP();
57 
58  /**
59  * Handle sending of messages. Call this regularly at a fixed frequency.
60  * @param t current time
61  */
62  void send(const hrt_abstime t);
63 
64  /// Handle possible FTP message
65  void handle_message(const mavlink_message_t *msg);
66 
67  typedef void (*ReceiveMessageFunc_t)(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data);
68 
69  /// @brief Sets up the server to run in unit test mode.
70  /// @param rcvmsgFunc Function which will be called to handle outgoing mavlink messages.
71  /// @param worker_data Data to pass to worker
72  void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, void *worker_data);
73 
74  /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload.
75  /// This needs to be packed, because it's typecasted from mavlink_file_transfer_protocol_t.payload, which starts
76  /// at a 3 byte offset, causing an unaligned access to seq_number and offset
77  struct __attribute__((__packed__)) PayloadHeader {
78  uint16_t seq_number; ///< sequence number for message
79  uint8_t session; ///< Session id for read and write commands
80  uint8_t opcode; ///< Command opcode
81  uint8_t size; ///< Size of data
82  uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message
83  uint8_t burst_complete; ///< Only used if req_opcode=kCmdBurstReadFile - 1: set of burst packets complete, 0: More burst packets coming.
84  uint8_t padding; ///< 32 bit aligment padding
85  uint32_t offset; ///< Offsets for List and Read commands
86  uint8_t data[]; ///< command data, varies by Opcode
87  };
88 
89  /// @brief Command opcodes
90  enum Opcode : uint8_t {
91  kCmdNone, ///< ignored, always acked
92  kCmdTerminateSession, ///< Terminates open Read session
93  kCmdResetSessions, ///< Terminates all open Read sessions
94  kCmdListDirectory, ///< List files in <path> from <offset>
95  kCmdOpenFileRO, ///< Opens file at <path> for reading, returns <session>
96  kCmdReadFile, ///< Reads <size> bytes from <offset> in <session>
97  kCmdCreateFile, ///< Creates file at <path> for writing, returns <session>
98  kCmdWriteFile, ///< Writes <size> bytes to <offset> in <session>
99  kCmdRemoveFile, ///< Remove file at <path>
100  kCmdCreateDirectory, ///< Creates directory at <path>
101  kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
102  kCmdOpenFileWO, ///< Opens file at <path> for writing, returns <session>
103  kCmdTruncateFile, ///< Truncate file at <path> to <offset> length
104  kCmdRename, ///< Rename <path1> to <path2>
105  kCmdCalcFileCRC32, ///< Calculate CRC32 for file at <path>
106  kCmdBurstReadFile, ///< Burst download session file
107 
108  kRspAck = 128, ///< Ack response
109  kRspNak ///< Nak response
110  };
111 
112  /// @brief Error codes returned in Nak response PayloadHeader.data[0].
113  enum ErrorCode : uint8_t {
115  kErrFail, ///< Unknown failure
116  kErrFailErrno, ///< Command failed, errno sent back in PayloadHeader.data[1]
117  kErrInvalidDataSize, ///< PayloadHeader.size is invalid
118  kErrInvalidSession, ///< Session is not currently open
119  kErrNoSessionsAvailable, ///< All available Sessions in use
120  kErrEOF, ///< Offset past end of file for List and Read commands
121  kErrUnknownCommand, ///< Unknown command opcode
122  kErrFailFileExists, ///< File exists already
123  kErrFailFileProtected ///< File is write protected
124  };
125 
126  unsigned get_size();
127 
128 private:
129  char *_data_as_cstring(PayloadHeader *payload);
130 
131  void _process_request(mavlink_file_transfer_protocol_t *ftp_req, uint8_t target_system_id, uint8_t target_comp_id);
132  void _reply(mavlink_file_transfer_protocol_t *ftp_req);
133  int _copy_file(const char *src_path, const char *dst_path, size_t length);
134 
135  ErrorCode _workList(PayloadHeader *payload, bool list_hidden = false);
136  ErrorCode _workOpen(PayloadHeader *payload, int oflag);
137  ErrorCode _workRead(PayloadHeader *payload);
138  ErrorCode _workBurst(PayloadHeader *payload, uint8_t target_system_id, uint8_t target_component_id);
139  ErrorCode _workWrite(PayloadHeader *payload);
140  ErrorCode _workTerminate(PayloadHeader *payload);
141  ErrorCode _workReset(PayloadHeader *payload);
142  ErrorCode _workRemoveDirectory(PayloadHeader *payload);
143  ErrorCode _workCreateDirectory(PayloadHeader *payload);
144  ErrorCode _workRemoveFile(PayloadHeader *payload);
145  ErrorCode _workTruncateFile(PayloadHeader *payload);
146  ErrorCode _workRename(PayloadHeader *payload);
147  ErrorCode _workCalcFileCRC32(PayloadHeader *payload);
148 
149  uint8_t _getServerSystemId(void);
150  uint8_t _getServerComponentId(void);
151  uint8_t _getServerChannel(void);
152 
153  /**
154  * make sure that the working buffers _work_buffer* are allocated
155  * @return true if buffers exist, false if allocation failed
156  */
157  bool _ensure_buffers_exist();
158 
159  static const char kDirentFile = 'F'; ///< Identifies File returned from List command
160  static const char kDirentDir = 'D'; ///< Identifies Directory returned from List command
161  static const char kDirentSkip = 'S'; ///< Identifies Skipped entry from List command
162 
163  /// @brief Maximum data size in RequestHeader::data
164  static const uint8_t kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader);
165 
166  struct SessionInfo {
167  int fd;
168  uint32_t file_size;
170  uint32_t stream_offset;
175  };
176  struct SessionInfo _session_info {}; ///< Session info, fd=-1 for no active session
177 
178  ReceiveMessageFunc_t _utRcvMsgFunc{}; ///< Unit test override for mavlink message sending
179  void *_worker_data{nullptr}; ///< Additional parameter to _utRcvMsgFunc;
180 
182 
183  /* do not allow copying this class */
184  MavlinkFTP(const MavlinkFTP &);
186 
187  /* work buffers: they're allocated as soon as we get the first request (lazy, since FTP is rarely used) */
188  char *_work_buffer1{nullptr};
189  static constexpr int _work_buffer1_len = kMaxDataLength;
190  char *_work_buffer2{nullptr};
191  static constexpr int _work_buffer2_len = 256;
192  hrt_abstime _last_work_buffer_access{0}; ///< timestamp when the buffers were last accessed
193 
194  // prepend a root directory to each file/dir access to avoid enumerating the full FS tree (e.g. on Linux).
195  // Note that requests can still fall outside of the root dir by using ../..
196 #ifdef MAVLINK_FTP_UNIT_TEST
197  static constexpr const char _root_dir[] = "";
198 #else
199  static constexpr const char _root_dir[] = PX4_ROOTFSDIR;
200 #endif
201  static constexpr const int _root_dir_len = sizeof(_root_dir) - 1;
202 
203  bool _last_reply_valid = false;
204  uint8_t _last_reply[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN - MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN
205  + sizeof(PayloadHeader) + sizeof(uint32_t)];
206 
207  // Mavlink test needs to be able to call send
208  friend class MavlinkFtpTest;
209 };
High-resolution timer with callouts and timekeeping.
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
uint8_t * data
Definition: dataman.cpp:149
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58