15 from mavros_msgs.msg
import ParamValue
16 from mavros_msgs.srv
import ParamPull, ParamPush, ParamGet, ParamSet
20 """Class representing one parameter""" 30 """Base class for param file parsers""" 35 """Returns a iterable of Parameters""" 36 raise NotImplementedError
38 def write(self, file_, parametes):
39 """Writes Parameters to file""" 40 raise NotImplementedError
44 """Parse MissionPlanner param files""" 49 skipinitialspace =
True 50 lineterminator =
'\r\n' 51 quoting = csv.QUOTE_NONE
54 to_numeric =
lambda x: float(x)
if '.' in x
else int(x)
56 for data
in csv.reader(file_, self.
CSVDialect):
57 if data[0].startswith(
'#'):
61 raise ValueError(
"wrong field count")
63 yield Parameter(data[0].strip(), to_numeric(data[1]));
65 def write(self, file_, parameters):
67 writer.writerow((
"#NOTE: " + time.strftime(
"%d.%m.%Y %T") ,))
69 writer.writerow((p.param_id, p.param_value))
73 """Parse QGC param files""" 78 skipinitialspace =
True 80 quoting = csv.QUOTE_NONE
83 to_numeric =
lambda x: float(x)
if '.' in x
else int(x)
85 for data
in csv.reader(file_, self.
CSVDialect):
86 if data[0].startswith(
'#'):
90 raise ValueError(
"wrong field count")
92 yield Parameter(data[2].strip(), to_numeric(data[3]));
94 def write(self, file_, parameters):
96 if isinstance(x, float):
98 elif isinstance(x, int):
101 raise ValueError(
"unknown type: " + repr(type(x)))
107 writer.writerow((
"# NOTE: " + time.strftime(
"%d.%m.%Y %T"), ))
108 writer.writerow((
"# Onboard parameters saved by mavparam for ({}, {})".
format(sysid, compid), ))
109 writer.writerow((
"# MAV ID" ,
"COMPONENT ID",
"PARAM NAME",
"VALUE",
"(TYPE)"))
111 writer.writerow((sysid, compid, p.param_id, p.param_value, to_type(p.param_value), ))
115 if ret.value.integer != 0:
116 return ret.value.integer
117 elif ret.value.real != 0.0:
118 return ret.value.real
126 ret = get(param_id=param_id)
127 except rospy.ServiceException
as ex:
128 raise IOError(str(ex))
131 raise IOError(
"Request failed.")
137 if isinstance(value, float):
138 val = ParamValue(integer=0, real=value)
140 val = ParamValue(integer=value, real=0.0)
144 ret = set(param_id=param_id, value=val)
145 except rospy.ServiceException
as ex:
146 raise IOError(str(ex))
149 raise IOError(
"Request failed.")
157 ret =
pull(force_pull=force_pull)
158 except rospy.ServiceException
as ex:
159 raise IOError(str(ex))
162 raise IOError(
"Request failed.")
166 return (ret.param_received,
167 sorted((
Parameter(k, v)
for k, v
in params.items()),
168 key=
lambda p: p.param_id)
181 except rospy.ServiceException
as ex:
182 raise IOError(str(ex))
185 raise IOError(
"Request failed.")
187 return ret.param_transfered
std::string format(const std::string &fmt, Args...args)
def param_set(param_id, value)
def write(self, file_, parametes)
def write(self, file_, parameters)
def param_get_all(force_pull=False)
def write(self, file_, parameters)
def __init__(self, param_id, param_value=0)
def param_set_list(param_list)