26 from std_srvs.srv
import Empty
27 from mavros_msgs.msg
import FileEntry
28 from mavros_msgs.srv
import FileOpen, FileClose, FileRead, FileList, FileOpenRequest, \
29 FileMakeDir, FileRemoveDir, FileRemove, FileWrite, FileTruncate, FileRename, \
39 raise IOError(ret.r_errno, os.strerror(ret.r_errno))
45 Note that current PX4 firmware only support two connections simultaneously. 56 def open(self, path, mode):
61 - 'cw': create excl & write
63 if mode == 'w' or mode == 'wb': 64 m = FileOpenRequest.MODE_WRITE 65 elif mode == 'r' or mode == 'rb':
66 m = FileOpenRequest.MODE_READ
68 m = FileOpenRequest.MODE_CREATE
70 raise ValueError("Unknown open mode: {}".format(m))
72 open_ = _get_proxy('open', FileOpen)
74 ret = open_(file_path=path, mode=m)
75 except rospy.ServiceException as ex:
76 raise IOError(str(ex))
78 _check_raise_errno(ret)
80 self._read = _get_proxy('read', FileRead)
81 self._write = _get_proxy('write', FileWrite)
92 close_ = _get_proxy('close', FileClose)
94 ret = close_(file_path=self.name)
95 except rospy.ServiceException as ex:
96 raise IOError(str(ex))
99 _check_raise_errno(ret)
101 def read(self, size=1):
103 ret = self._read(file_path=self.name, offset=self.offset, size=size)
104 except rospy.ServiceException as ex:
105 raise IOError(str(ex))
107 _check_raise_errno(ret)
108 self.offset += len(ret.data)
109 return bytearray(ret.data)
111 def write(self, bin_data):
112 data_len = len(bin_data)
114 ret = self._write(file_path=self.name, offset=self.offset, data=bin_data)
115 except rospy.ServiceException as ex:
116 raise IOError(str(ex))
118 _check_raise_errno(ret)
119 self.offset += data_len
120 if self.offset > self.size:
121 self.size = self.offset
126 def seek(self, offset, whence=os.SEEK_SET):
127 if whence is os.SEEK_SET:
129 elif whence is os.SEEK_END:
130 self.offset = offset + self.size
131 elif whence is os.SEEK_CUR:
132 self.offset += offset
134 raise ValueError("Unknown whence")
136 def truncate(self, size=0):
137 truncate_ = _get_proxy('truncate', FileTruncate)
139 ret = truncate_(file_path=self.name, length=size)
140 except rospy.ServiceException as ex:
141 raise IOError(str(ex))
143 _check_raise_errno(ret)
147 return self.name is None
152 def __exit__(self, exc_type, exc_value, traceback):
156 def open(path, mode):
157 """Open file on FCU"""
158 return FTPFile(path, mode)
162 """List directory :path: contents"""
164 list_ = _get_proxy('list', FileList)
165 ret = list_(dir_path=path)
166 except rospy.ServiceException as ex:
167 raise IOError(str(ex))
169 _check_raise_errno(ret)
174 """Remove :path: file"""
175 remove = _get_proxy('remove', FileRemove)
177 ret = remove(file_path=path)
178 except rospy.ServiceException as ex:
179 raise IOError(str(ex))
181 _check_raise_errno(ret)
185 """Create directory :path:"""
186 mkdir_ = _get_proxy('mkdir', FileMakeDir)
188 ret = mkdir_(dir_path=path)
189 except rospy.ServiceException as ex:
190 raise IOError(str(ex))
192 _check_raise_errno(ret)
196 """Remove directory :path:"""
197 rmdir_ = _get_proxy('rmdir', FileRemoveDir)
199 ret = rmdir_(dir_path=path)
200 except rospy.ServiceException as ex:
201 raise IOError(str(ex))
203 _check_raise_errno(ret)
206 def rename(old_path, new_path):
207 """Rename :old_path: to :new_path:"""
208 rename_ = _get_proxy('rename', FileRename)
210 ret = rename_(old_path=old_path, new_path=new_path)
211 except rospy.ServiceException as ex:
212 raise IOError(str(ex))
214 _check_raise_errno(ret)
218 """Calculate CRC32 for :path:"""
219 checksum_ = _get_proxy('checksum', FileChecksum)
221 ret = checksum_(file_path=path)
222 except rospy.ServiceException as ex:
223 raise IOError(str(ex))
225 _check_raise_errno(ret)
230 reset = _get_proxy('reset', Empty)
233 except rospy.ServiceException as ex:
234 raise IOError(str(ex))
def __init__(self, name, mode)
def _check_raise_errno(ret)
def _get_proxy(service, type)
def open(self, path, mode)