ftp.py
Go to the documentation of this file.
00001 # -*- python -*-
00002 # vim:set ts=4 sw=4 et:
00003 #
00004 # Copyright 2014 Vladimir Ermakov.
00005 #
00006 # This program is free software; you can redistribute it and/or modify
00007 # it under the terms of the GNU General Public License as published by
00008 # the Free Software Foundation; either version 3 of the License, or
00009 # (at your option) any later version.
00010 #
00011 # This program is distributed in the hope that it will be useful, but
00012 # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
00013 # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
00014 # for more details.
00015 #
00016 # You should have received a copy of the GNU General Public License along
00017 # with this program; if not, write to the Free Software Foundation, Inc.,
00018 # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
00019 
00020 import os
00021 import rospy
00022 
00023 from std_srvs.srv import Empty
00024 from mavros.msg import FileEntry
00025 from mavros.srv import FileOpen, FileClose, FileRead, FileList, FileOpenRequest, \
00026     FileMakeDir, FileRemoveDir, FileRemove, FileWrite, FileTruncate, FileRename, \
00027     FileChecksum
00028 
00029 
00030 def _check_raise_errno(ret):
00031         if not ret.success:
00032             raise IOError(ret.r_errno, os.strerror(ret.r_errno))
00033 
00034 
00035 class FTPFile(object):
00036     def __init__(self, name, mode, ns="/mavros"):
00037         self.name = None
00038         self.mode = mode
00039         self.mavros_ns = ns
00040         self.open(name, mode)
00041 
00042     def __del__(self):
00043         self.close()
00044 
00045     def open(self, path, mode):
00046         """
00047         Supported modes:
00048             - 'w': write binary
00049             - 'r': read binary
00050             - 'cw': create excl & write
00051         """
00052         if mode == 'w' or mode == 'wb':
00053             m = FileOpenRequest.MODE_WRITE
00054         elif mode == 'r' or mode == 'rb':
00055             m = FileOpenRequest.MODE_READ
00056         elif mode == 'cw':
00057             m = FileOpenRequest.MODE_CREATE
00058         else:
00059             raise ValueError("Unknown open mode: {}".format(m))
00060 
00061         try:
00062             open_cl = rospy.ServiceProxy(self.mavros_ns + "/ftp/open", FileOpen)
00063             ret = open_cl(file_path=path, mode=m)
00064         except rospy.ServiceException as ex:
00065             raise IOError(str(ex))
00066 
00067         _check_raise_errno(ret)
00068 
00069         self._read_cl = rospy.ServiceProxy(self.mavros_ns + "/ftp/read", FileRead)
00070         self._write_cl = rospy.ServiceProxy(self.mavros_ns + "/ftp/write", FileWrite)
00071 
00072         self.name = path
00073         self.mode = mode
00074         self.size = ret.size
00075         self.offset = 0
00076 
00077     def close(self):
00078         if self.closed:
00079             return
00080 
00081         try:
00082             close_cl = rospy.ServiceProxy(self.mavros_ns + "/ftp/close", FileClose)
00083             ret = close_cl(file_path=self.name)
00084         except rospy.ServiceException as ex:
00085             raise IOError(str(ex))
00086 
00087         self.name = None
00088         _check_raise_errno(ret)
00089 
00090     def read(self, size=1):
00091         try:
00092             ret = self._read_cl(file_path=self.name, offset=self.offset, size=size)
00093         except rospy.ServiceException as ex:
00094             raise IOError(str(ex))
00095 
00096         _check_raise_errno(ret)
00097         self.offset += len(ret.data)
00098         return bytearray(ret.data)
00099 
00100     def write(self, bin_data):
00101         data_len = len(bin_data)
00102         try:
00103             ret = self._write_cl(file_path=self.name, offset=self.offset, data=bin_data)
00104         except rospy.ServiceException as ex:
00105             raise IOError(str(ex))
00106 
00107         _check_raise_errno(ret)
00108         self.offset += data_len
00109         if self.offset > self.size:
00110             self.size = self.offset
00111 
00112     def tell(self):
00113         return self.offset
00114 
00115     def seek(self, offset, whence=os.SEEK_SET):
00116         if whence is os.SEEK_SET:
00117             self.offset = offset
00118         elif whence is os.SEEK_END:
00119             self.offset = offset + self.size
00120         elif whence is os.SEEK_CUR:
00121             self.offset += offset
00122         else:
00123             raise ValueError("Unknown whence")
00124 
00125     def truncate(self, size=0):
00126         try:
00127             truncate_cl = rospy.ServiceProxy(self.mavros_ns + "/ftp/truncate", FileTruncate)
00128             ret = truncate_cl(file_path=self.name, length=size)
00129         except rospy.ServiceException as ex:
00130             raise IOError(str(ex))
00131 
00132         _check_raise_errno(ret)
00133 
00134     @property
00135     def closed(self):
00136         return self.name is None
00137 
00138     def __enter__(self):
00139         return self
00140 
00141     def __exit__(self, exc_type, exc_value, traceback):
00142         self.close()
00143 
00144 
00145 def ftp_listdir(path, ns="/mavros"):
00146     """List directory :path: contents"""
00147     try:
00148         list_cl = rospy.ServiceProxy(ns + "/ftp/list", FileList)
00149         ret = list_cl(dir_path=path)
00150     except rospy.ServiceException as ex:
00151         raise IOError(str(ex))
00152 
00153     _check_raise_errno(ret)
00154     return ret.list
00155 
00156 
00157 def ftp_unlink(path, ns="/mavros"):
00158     """Remove :path: file"""
00159     try:
00160         remove_cl = rospy.ServiceProxy(ns + "/ftp/remove", FileRemove)
00161         ret = remove_cl(file_path=path)
00162     except rospy.ServiceException as ex:
00163         raise IOError(str(ex))
00164 
00165     _check_raise_errno(ret)
00166 
00167 
00168 def ftp_mkdir(path, ns="/mavros"):
00169     """Create directory :path:"""
00170     try:
00171         mkdir_cl = rospy.ServiceProxy(ns + "/ftp/mkdir", FileMakeDir)
00172         ret = mkdir_cl(dir_path=path)
00173     except rospy.ServiceException as ex:
00174         raise IOError(str(ex))
00175 
00176     _check_raise_errno(ret)
00177 
00178 
00179 def ftp_rmdir(path, ns="/mavros"):
00180     """Remove directory :path:"""
00181     try:
00182         rmdir_cl = rospy.ServiceProxy(ns + "/ftp/rmdir", FileRemoveDir)
00183         ret = rmdir_cl(dir_path=path)
00184     except rospy.ServiceException as ex:
00185         raise IOError(str(ex))
00186 
00187     _check_raise_errno(ret)
00188 
00189 
00190 def ftp_rename(old_path, new_path, ns="/mavros"):
00191     """Rename :old_path: to :new_path:"""
00192     try:
00193         rename_cl = rospy.ServiceProxy(ns + "/ftp/rename", FileRename)
00194         ret = rename_cl(old_path=old_path, new_path=new_path)
00195     except rospy.ServiceException as ex:
00196         raise IOError(str(ex))
00197 
00198     _check_raise_errno(ret)
00199 
00200 
00201 def ftp_checksum(path, ns="/mavros"):
00202     """Calculate CRC32 for :path:"""
00203     try:
00204         checksum_cl = rospy.ServiceProxy(ns + "/ftp/checksum", FileChecksum)
00205         ret = checksum_cl(file_path=path)
00206     except rospy.ServiceException as ex:
00207         raise IOError(str(ex))
00208 
00209     _check_raise_errno(ret)
00210     return ret.crc32
00211 
00212 
00213 def ftp_reset_server(ns="/mavros"):
00214     try:
00215         reset_cl = rospy.ServiceProxy(ns + "/ftp/reset", Empty)
00216         reset_cl()
00217     except rospy.ServiceException as ex:
00218         raise IOError(str(ex))


mavros
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:13