Firmware
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 
38 
39 #include <dirent.h>
40 #include <queue.h>
41 
42 #include <px4_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 
53 {
54 public:
55  MavlinkFTP(Mavlink *mavlink);
56  ~MavlinkFTP();
57 
62  void send(const hrt_abstime t);
63 
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 
72  void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, void *worker_data);
73 
77  struct __attribute__((__packed__)) PayloadHeader {
78  uint16_t seq_number;
79  uint8_t session;
80  uint8_t opcode;
81  uint8_t size;
82  uint8_t req_opcode;
83  uint8_t burst_complete;
84  uint8_t padding;
85  uint32_t offset;
86  uint8_t data[];
87  };
88 
90  enum Opcode : uint8_t {
107 
108  kRspAck = 128,
110  };
111 
113  enum ErrorCode : uint8_t {
114  kErrNone,
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);
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);
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 
157  bool _ensure_buffers_exist();
158 
159  static const char kDirentFile = 'F';
160  static const char kDirentDir = 'D';
161  static const char kDirentSkip = 'S';
162 
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;
169  bool stream_download;
170  uint32_t stream_offset;
171  uint16_t stream_seq_number;
172  uint8_t stream_target_system_id;
173  unsigned stream_chunk_transmitted;
174  };
175  struct SessionInfo _session_info {};
176 
177  ReceiveMessageFunc_t _utRcvMsgFunc{};
178  void *_worker_data{nullptr};
179 
180  Mavlink *_mavlink;
181 
182  /* do not allow copying this class */
183  MavlinkFTP(const MavlinkFTP &);
184  MavlinkFTP operator=(const MavlinkFTP &);
185 
186  /* work buffers: they're allocated as soon as we get the first request (lazy, since FTP is rarely used) */
187  char *_work_buffer1{nullptr};
188  static constexpr int _work_buffer1_len = kMaxDataLength;
189  char *_work_buffer2{nullptr};
190  static constexpr int _work_buffer2_len = 256;
191  hrt_abstime _last_work_buffer_access{0};
192 
193  // prepend a root directory to each file/dir access to avoid enumerating the full FS tree (e.g. on Linux).
194  // Note that requests can still fall outside of the root dir by using ../..
195 #ifdef MAVLINK_FTP_UNIT_TEST
196  static constexpr const char _root_dir[] = "";
197 #else
198  static constexpr const char _root_dir[] = PX4_ROOTFSDIR;
199 #endif
200  static constexpr const int _root_dir_len = sizeof(_root_dir) - 1;
201 
202  bool _last_reply_valid = false;
203  uint8_t _last_reply[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN - MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN
204  + sizeof(PayloadHeader) + sizeof(uint32_t)];
205 
206  // Mavlink test needs to be able to call send
207  friend class MavlinkFtpTest;
208 };
Terminates open Read session.
Definition: mavlink_ftp.h:92
Terminates all open Read sessions.
Definition: mavlink_ftp.h:93
ignored, always acked
Definition: mavlink_ftp.h:91
Rename <path1> to <path2>
Definition: mavlink_ftp.h:104
File is write protected.
Definition: mavlink_ftp.h:123
void send(const hrt_abstime t)
Handle sending of messages.
Definition: mavlink_ftp.cpp:959
Ack response.
Definition: mavlink_ftp.h:108
Opcode
Command opcodes.
Definition: mavlink_ftp.h:90
Definition: mavlink_ftp_test.h:43
Unknown command opcode.
Definition: mavlink_ftp.h:121
void handle_message(const mavlink_message_t *msg)
Handle possible FTP message.
Definition: mavlink_ftp.cpp:126
File exists already.
Definition: mavlink_ftp.h:122
ErrorCode
Error codes returned in Nak response PayloadHeader.data[0].
Definition: mavlink_ftp.h:113
List files in <path> from <offset>
Definition: mavlink_ftp.h:94
All available Sessions in use.
Definition: mavlink_ftp.h:119
High-resolution timer with callouts and timekeeping.
Definition: crtp.h:57
Session is not currently open.
Definition: mavlink_ftp.h:118
Generally used magic defines.
Unknown failure.
Definition: mavlink_ftp.h:115
Writes <size> bytes to <offset> in <session>
Definition: mavlink_ftp.h:98
Creates directory at <path>
Definition: mavlink_ftp.h:100
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
Reads <size> bytes from <offset> in <session>
Definition: mavlink_ftp.h:96
Offset past end of file for List and Read commands.
Definition: mavlink_ftp.h:120
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
PayloadHeader.size is invalid.
Definition: mavlink_ftp.h:117
Creates file at <path> for writing, returns <session>
Definition: mavlink_ftp.h:97
Truncate file at <path> to <offset> length.
Definition: mavlink_ftp.h:103
Burst download session file.
Definition: mavlink_ftp.h:106
void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, void *worker_data)
Sets up the server to run in unit test mode.
Command failed, errno sent back in PayloadHeader.data[1].
Definition: mavlink_ftp.h:116
MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL mes...
Definition: mavlink_ftp.h:52
Opens file at <path> for reading, returns <session>
Definition: mavlink_ftp.h:95
Opens file at <path> for writing, returns <session>
Definition: mavlink_ftp.h:102
Calculate CRC32 for file at <path>
Definition: mavlink_ftp.h:105
Nak response.
Definition: mavlink_ftp.h:109
Removes Directory at <path>, must be empty.
Definition: mavlink_ftp.h:101
Remove file at <path>
Definition: mavlink_ftp.h:99