ftp.py
Go to the documentation of this file.
00001 # -*- coding: utf-8 -*-
00002 # vim:set ts=4 sw=4 et:
00003 #
00004 # Copyright 2014,2015 Vladimir Ermakov.
00005 #
00006 # This file is part of the mavros package and subject to the license terms
00007 # in the top-level LICENSE file of the mavros repository.
00008 # https://github.com/mavlink/mavros/tree/master/LICENSE.md
00009 
00010 __all__ = (
00011     'FTPFile',
00012     'open',
00013     'listdir',
00014     'unlink',
00015     'mkdir',
00016     'rmdir',
00017     'rename',
00018     'checksum',
00019     'reset_server'
00020 )
00021 
00022 import os
00023 import rospy
00024 import mavros
00025 
00026 from std_srvs.srv import Empty
00027 from mavros_msgs.msg import FileEntry
00028 from mavros_msgs.srv import FileOpen, FileClose, FileRead, FileList, FileOpenRequest, \
00029     FileMakeDir, FileRemoveDir, FileRemove, FileWrite, FileTruncate, FileRename, \
00030     FileChecksum
00031 
00032 
00033 def _get_proxy(service, type):
00034     return rospy.ServiceProxy(mavros.get_topic('ftp', service), type)
00035 
00036 
00037 def _check_raise_errno(ret):
00038         if not ret.success:
00039             raise IOError(ret.r_errno, os.strerror(ret.r_errno))
00040 
00041 
00042 class FTPFile(object):
00043     """
00044     FCU file object.
00045     Note that current PX4 firmware only support two connections simultaneously.
00046     """
00047 
00048     def __init__(self, name, mode):
00049         self.name = None
00050         self.mode = mode
00051         self.open(name, mode)
00052 
00053     def __del__(self):
00054         self.close()
00055 
00056     def open(self, path, mode):
00057         """
00058         Supported modes:
00059             - 'w': write binary
00060             - 'r': read binary
00061             - 'cw': create excl & write
00062         """
00063         if mode == 'w' or mode == 'wb':
00064             m = FileOpenRequest.MODE_WRITE
00065         elif mode == 'r' or mode == 'rb':
00066             m = FileOpenRequest.MODE_READ
00067         elif mode == 'cw':
00068             m = FileOpenRequest.MODE_CREATE
00069         else:
00070             raise ValueError("Unknown open mode: {}".format(m))
00071 
00072         open_ = _get_proxy('open', FileOpen)
00073         try:
00074             ret = open_(file_path=path, mode=m)
00075         except rospy.ServiceException as ex:
00076             raise IOError(str(ex))
00077 
00078         _check_raise_errno(ret)
00079 
00080         self._read = _get_proxy('read', FileRead)
00081         self._write = _get_proxy('write', FileWrite)
00082 
00083         self.name = path
00084         self.mode = mode
00085         self.size = ret.size
00086         self.offset = 0
00087 
00088     def close(self):
00089         if self.closed:
00090             return
00091 
00092         close_ = _get_proxy('close', FileClose)
00093         try:
00094             ret = close_(file_path=self.name)
00095         except rospy.ServiceException as ex:
00096             raise IOError(str(ex))
00097 
00098         self.name = None
00099         _check_raise_errno(ret)
00100 
00101     def read(self, size=1):
00102         try:
00103             ret = self._read(file_path=self.name, offset=self.offset, size=size)
00104         except rospy.ServiceException as ex:
00105             raise IOError(str(ex))
00106 
00107         _check_raise_errno(ret)
00108         self.offset += len(ret.data)
00109         return bytearray(ret.data)
00110 
00111     def write(self, bin_data):
00112         data_len = len(bin_data)
00113         try:
00114             ret = self._write(file_path=self.name, offset=self.offset, data=bin_data)
00115         except rospy.ServiceException as ex:
00116             raise IOError(str(ex))
00117 
00118         _check_raise_errno(ret)
00119         self.offset += data_len
00120         if self.offset > self.size:
00121             self.size = self.offset
00122 
00123     def tell(self):
00124         return self.offset
00125 
00126     def seek(self, offset, whence=os.SEEK_SET):
00127         if whence is os.SEEK_SET:
00128             self.offset = offset
00129         elif whence is os.SEEK_END:
00130             self.offset = offset + self.size
00131         elif whence is os.SEEK_CUR:
00132             self.offset += offset
00133         else:
00134             raise ValueError("Unknown whence")
00135 
00136     def truncate(self, size=0):
00137         truncate_ = _get_proxy('truncate', FileTruncate)
00138         try:
00139             ret = truncate_(file_path=self.name, length=size)
00140         except rospy.ServiceException as ex:
00141             raise IOError(str(ex))
00142 
00143         _check_raise_errno(ret)
00144 
00145     @property
00146     def closed(self):
00147         return self.name is None
00148 
00149     def __enter__(self):
00150         return self
00151 
00152     def __exit__(self, exc_type, exc_value, traceback):
00153         self.close()
00154 
00155 
00156 def open(path, mode):
00157     """Open file on FCU"""
00158     return FTPFile(path, mode)
00159 
00160 
00161 def listdir(path):
00162     """List directory :path: contents"""
00163     try:
00164         list_ = _get_proxy('list', FileList)
00165         ret = list_(dir_path=path)
00166     except rospy.ServiceException as ex:
00167         raise IOError(str(ex))
00168 
00169     _check_raise_errno(ret)
00170     return ret.list
00171 
00172 
00173 def unlink(path):
00174     """Remove :path: file"""
00175     remove = _get_proxy('remove', FileRemove)
00176     try:
00177         ret = remove(file_path=path)
00178     except rospy.ServiceException as ex:
00179         raise IOError(str(ex))
00180 
00181     _check_raise_errno(ret)
00182 
00183 
00184 def mkdir(path):
00185     """Create directory :path:"""
00186     mkdir_ = _get_proxy('mkdir', FileMakeDir)
00187     try:
00188         ret = mkdir_(dir_path=path)
00189     except rospy.ServiceException as ex:
00190         raise IOError(str(ex))
00191 
00192     _check_raise_errno(ret)
00193 
00194 
00195 def rmdir(path):
00196     """Remove directory :path:"""
00197     rmdir_ = _get_proxy('rmdir', FileRemoveDir)
00198     try:
00199         ret = rmdir_(dir_path=path)
00200     except rospy.ServiceException as ex:
00201         raise IOError(str(ex))
00202 
00203     _check_raise_errno(ret)
00204 
00205 
00206 def rename(old_path, new_path):
00207     """Rename :old_path: to :new_path:"""
00208     rename_ = _get_proxy('rename', FileRename)
00209     try:
00210         ret = rename_(old_path=old_path, new_path=new_path)
00211     except rospy.ServiceException as ex:
00212         raise IOError(str(ex))
00213 
00214     _check_raise_errno(ret)
00215 
00216 
00217 def checksum(path):
00218     """Calculate CRC32 for :path:"""
00219     checksum_ = _get_proxy('checksum', FileChecksum)
00220     try:
00221         ret = checksum_(file_path=path)
00222     except rospy.ServiceException as ex:
00223         raise IOError(str(ex))
00224 
00225     _check_raise_errno(ret)
00226     return ret.crc32
00227 
00228 
00229 def reset_server():
00230     reset = _get_proxy('reset', Empty)
00231     try:
00232         reset()
00233     except rospy.ServiceException as ex:
00234         raise IOError(str(ex))


mavros
Author(s): Vladimir Ermakov
autogenerated on Thu Feb 9 2017 04:00:17