Skip to content

Commit

Permalink
mavparam #262: use get_topic()
Browse files Browse the repository at this point in the history
  • Loading branch information
vooon committed Apr 1, 2015
1 parent 65660e8 commit c114fe6
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 34 deletions.
19 changes: 7 additions & 12 deletions mavros/scripts/mavparam
Original file line number Diff line number Diff line change
Expand Up @@ -33,19 +33,15 @@ def get_param_file_io(args):


def do_load(args):
rospy.init_node("mavparam", anonymous=True)

param_file = get_param_file_io(args)
with args.file:
param_transfered = param_set_list(param_file.read(args.file), args.mavros_ns)
param_transfered = param_set_list(param_file.read(args.file))

print_if(args.verbose, "Parameters transfered:", param_transfered)


def do_dump(args):
rospy.init_node("mavparam", anonymous=True)

param_received, param_list = param_get_all(args.force, args.mavros_ns)
param_received, param_list = param_get_all(args.force)
print_if(args.verbose, "Parameters received:", param_received)

param_file = get_param_file_io(args)
Expand All @@ -54,20 +50,16 @@ def do_dump(args):


def do_get(args):
rospy.init_node("mavparam", anonymous=True)

print(param_get(args.param_id, args.mavros_ns))
print(param_get(args.param_id))


def do_set(args):
rospy.init_node("mavparam", anonymous=True)

if '.' in args.value:
val = float(args.value)
else:
val = int(args.value)

print(param_set(args.param_id, val, args.mavros_ns))
print(param_set(args.param_id, val))


def main():
Expand Down Expand Up @@ -101,6 +93,9 @@ def main():
set_args.add_argument('value', help="new value")

args = parser.parse_args(rospy.myargv(argv=sys.argv)[1:])

rospy.init_node("mavparam", anonymous=True)
mavros.set_namespace(args.mavros_ns)
args.func(args)


Expand Down
41 changes: 19 additions & 22 deletions mavros/src/mavros/param.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# -*- python -*-
# -*- coding: utf-8 -*-
# vim:set ts=4 sw=4 et:
#
# Copyright 2014 Vladimir Ermakov.
Expand All @@ -10,6 +10,7 @@
import csv
import time
import rospy
import mavros

from mavros.srv import ParamPull, ParamPush, ParamGet, ParamSet

Expand Down Expand Up @@ -77,9 +78,6 @@ class CSVDialect(csv.Dialect):
lineterminator = '\n'
quoting = csv.QUOTE_NONE

def __init__(self, args):
self.mavros_ns = args.mavros_ns

def read(self, file_):
to_numeric = lambda x: float(x) if '.' in x else int(x)

Expand All @@ -101,8 +99,8 @@ def to_type(x):
else:
raise ValueError("unknown type: " + repr(type(x)))

sysid = rospy.get_param(self.mavros_ns + "/target_system_id", 1)
compid = rospy.get_param(self.mavros_ns + "/target_component_id", 1)
sysid = rospy.get_param(mavros.get_topic('target_system_id'), 1)
compid = rospy.get_param(mavros.get_topic('target_component_id'), 1)

writer = csv.writer(file_, self.CSVDialect)
writer.writerow(("# NOTE: " + time.strftime("%d.%m.%Y %T"), ))
Expand All @@ -121,10 +119,10 @@ def param_ret_value(ret):
return 0


def param_get(param_id, ns="/mavros"):
def param_get(param_id):
try:
get_cl = rospy.ServiceProxy(ns + "/param/get", ParamGet)
ret = get_cl(param_id=param_id)
get = rospy.ServiceProxy(mavros.get_topic('param', 'get'), ParamGet)
ret = get(param_id=param_id)
except rospy.ServiceException as ex:
raise IOError(str(ex))

Expand All @@ -134,7 +132,7 @@ def param_get(param_id, ns="/mavros"):
return param_ret_value(ret)


def param_set(param_id, value, ns="/mavros"):
def param_set(param_id, value):
if isinstance(value, float):
val_f = value
val_i = 0
Expand All @@ -143,11 +141,10 @@ def param_set(param_id, value, ns="/mavros"):
val_i = value

try:
set_cl = rospy.ServiceProxy(ns + "/param/set", ParamSet)
ret = set_cl(param_id=param_id,
set = rospy.ServiceProxy(mavros.get_topic('param', 'set'), ParamSet)
ret = set(param_id=param_id,
integer=val_i,
real=val_f
)
real=val_f)
except rospy.ServiceException as ex:
raise IOError(str(ex))

Expand All @@ -157,32 +154,32 @@ def param_set(param_id, value, ns="/mavros"):
return param_ret_value(ret)


def param_get_all(force_pull=False, ns="/mavros"):
def param_get_all(force_pull=False):
try:
pull_cl = rospy.ServiceProxy(ns + "/param/pull", ParamPull)
ret = pull_cl(force_pull=force_pull)
pull = rospy.ServiceProxy(mavros.get_topic('param', 'pull'), ParamPull)
ret = pull(force_pull=force_pull)
except rospy.ServiceException as ex:
raise IOError(str(ex))

if not ret.success:
raise IOError("Request failed.")

params = rospy.get_param(ns + "/param")
params = rospy.get_param(mavros.get_topic('param'))

return (ret.param_received,
sorted((Parameter(k, v) for k, v in params.iteritems()),
cmp=lambda x, y: cmp(x.param_id, y.param_id))
)

def param_set_list(param_list, ns="/mavros"):
def param_set_list(param_list):
# 1. load parameters to parameter server
for p in param_list:
rospy.set_param(ns + "/param/" + p.param_id, p.param_value)
rospy.set_param(mavros.get_topic('param', p.param_id), p.param_value)

# 2. request push all
try:
push_cl = rospy.ServiceProxy(ns + "/param/push", ParamPush)
ret = push_cl()
push = rospy.ServiceProxy(mavros.get_topic('param', 'push'), ParamPush)
ret = push()
except rospy.ServiceException as ex:
raise IOError(str(ex))

Expand Down

0 comments on commit c114fe6

Please sign in to comment.