Skip to content

Commit

Permalink
scripts: mavftp: Add upload subcommand.
Browse files Browse the repository at this point in the history
Issue #128.
  • Loading branch information
vooon committed Sep 22, 2014
1 parent 5e8a032 commit badd3f7
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 10 deletions.
21 changes: 13 additions & 8 deletions mavros/scripts/mavftp
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,6 @@ from mavros.utils import *
from mavros.ftp import *


def check_ret(operation, ret):
if not ret.success:
fault(operation, "failed:", os.strerror(ret.r_errno))

# -*- subcommand handlers -*-


def do_list(args):
rospy.init_node("mavftp", anonymous=True)

Expand Down Expand Up @@ -79,7 +72,18 @@ def do_rmdir(args):


def do_upload(args):
raise NotImplementedError
rospy.init_node("mavftp", anonymous=True)

mode = 'cw' if args.no_overwrite else 'w'

with args.file as from_fd:
with FTPFile(args.path, mode) as to_fd:
while True:
buf = from_fd.read(1024)
if len(buf) == 0:
break;

to_fd.write(buf)


def main():
Expand Down Expand Up @@ -113,6 +117,7 @@ def main():
upload_args.set_defaults(func=do_upload)
upload_args.add_argument('file', type=argparse.FileType('rb'), help="file to send")
upload_args.add_argument('path', type=str, help="save path")
upload_args.add_argument('-n', '--no-overwrite', action="store_true", help="do not overwrite existing file")

reset_args = subarg.add_parser('reset', help="reset")
reset_args.set_defaults(func=do_reset)
Expand Down
3 changes: 1 addition & 2 deletions mavros/src/mavros/ftp.py
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,6 @@ def ftp_unlink(path, ns="/mavros"):
raise IOError(str(ex))

_check_raise_errno(ret)
return ret.list


def ftp_mkdir(path, ns="/mavros"):
Expand Down Expand Up @@ -202,7 +201,7 @@ def ftp_rename(old_path, new_path, ns="/mavros"):
def ftp_checksum(path, ns="/mavros"):
"""Calculate CRC32 for :path:"""
try:
checksum_cl = rospy.ServiceProxy(ns + "/ftp/rename", FileChecksum)
checksum_cl = rospy.ServiceProxy(ns + "/ftp/checksum", FileChecksum)
ret = checksum_cl(file_path=path)
except rospy.ServiceException as ex:
raise IOError(str(ex))
Expand Down

0 comments on commit badd3f7

Please # to comment.