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))
74 ret = open_(file_path=path, mode=m)
75 except rospy.ServiceException
as ex:
76 raise IOError(str(ex))
94 ret = close_(file_path=self.
name)
95 except rospy.ServiceException
as ex:
96 raise IOError(str(ex))
104 except rospy.ServiceException
as ex:
105 raise IOError(str(ex))
109 return bytearray(ret.data)
112 data_len =
len(bin_data)
115 except rospy.ServiceException
as ex:
116 raise IOError(str(ex))
126 def seek(self, offset, whence=os.SEEK_SET):
127 if whence
is os.SEEK_SET:
129 elif whence
is os.SEEK_END:
131 elif whence
is os.SEEK_CUR:
134 raise ValueError(
"Unknown whence")
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))
147 return self.
name is None
152 def __exit__(self, exc_type, exc_value, traceback):
157 """Open file on FCU"""
162 """List directory :path: contents"""
165 ret = list_(dir_path=path)
166 except rospy.ServiceException
as ex:
167 raise IOError(str(ex))
174 """Remove :path: file"""
177 ret = remove(file_path=path)
178 except rospy.ServiceException
as ex:
179 raise IOError(str(ex))
185 """Create directory :path:"""
188 ret = mkdir_(dir_path=path)
189 except rospy.ServiceException
as ex:
190 raise IOError(str(ex))
196 """Remove directory :path:"""
199 ret = rmdir_(dir_path=path)
200 except rospy.ServiceException
as ex:
201 raise IOError(str(ex))
207 """Rename :old_path: to :new_path:"""
210 ret = rename_(old_path=old_path, new_path=new_path)
211 except rospy.ServiceException
as ex:
212 raise IOError(str(ex))
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))
233 except rospy.ServiceException
as ex:
234 raise IOError(str(ex))