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 MavProxy 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 file_.write(
"#NOTE: " + time.strftime(
"%d.%m.%Y %T") + self.CSVDialect.lineterminator)
69 writer.writerow((p.param_id, p.param_value))
73 """Parse MissionPlanner param files""" 78 skipinitialspace =
True 79 lineterminator =
'\r\n' 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[0].strip(), to_numeric(data[1]));
94 def write(self, file_, parameters):
96 writer.writerow((
"#NOTE: " + time.strftime(
"%d.%m.%Y %T") ,))
98 writer.writerow((p.param_id, p.param_value))
102 """Parse QGC param files""" 107 skipinitialspace =
True 108 lineterminator =
'\n' 109 quoting = csv.QUOTE_NONE
112 to_numeric =
lambda x: float(x)
if '.' in x
else int(x)
114 for data
in csv.reader(file_, self.
CSVDialect):
115 if data[0].startswith(
'#'):
119 raise ValueError(
"wrong field count")
121 yield Parameter(data[2].strip(), to_numeric(data[3]));
125 if isinstance(x, float):
127 elif isinstance(x, int):
130 raise ValueError(
"unknown type: " + repr(type(x)))
136 writer.writerow((
"# NOTE: " + time.strftime(
"%d.%m.%Y %T"), ))
137 writer.writerow((
"# Onboard parameters saved by mavparam for ({}, {})".
format(sysid, compid), ))
138 writer.writerow((
"# MAV ID" ,
"COMPONENT ID",
"PARAM NAME",
"VALUE",
"(TYPE)"))
140 writer.writerow((sysid, compid, p.param_id, p.param_value, to_type(p.param_value), ))
144 if ret.value.integer != 0:
145 return ret.value.integer
146 elif ret.value.real != 0.0:
147 return ret.value.real
155 ret = get(param_id=param_id)
156 except rospy.ServiceException
as ex:
157 raise IOError(str(ex))
160 raise IOError(
"Request failed.")
166 if isinstance(value, float):
167 val = ParamValue(integer=0, real=value)
169 val = ParamValue(integer=value, real=0.0)
173 ret = set(param_id=param_id, value=val)
174 except rospy.ServiceException
as ex:
175 raise IOError(str(ex))
178 raise IOError(
"Request failed.")
186 ret =
pull(force_pull=force_pull)
187 except rospy.ServiceException
as ex:
188 raise IOError(str(ex))
191 raise IOError(
"Request failed.")
195 return (ret.param_received,
196 sorted((
Parameter(k, v)
for k, v
in params.items()),
197 key=
lambda p: p.param_id)
210 except rospy.ServiceException
as ex:
211 raise IOError(str(ex))
214 raise IOError(
"Request failed.")
216 return ret.param_transfered
def write(self, file_, parameters)
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)