2 module for loading/saving sets of mavlink parameters 4 from __future__
import print_function
7 import fnmatch, math, time, struct
8 from pymavlink
import mavutil
12 dict.__init__(self, args)
14 self.
exclude_load = [
'SYSID_SW_MREV',
'SYS_NUM_RESETS',
'ARSPD_OFFSET',
'GND_ABS_PRESS',
15 'GND_TEMP',
'CMD_TOTAL',
'CMD_INDEX',
'LOG_LASTFILE',
'FENCE_TOTAL',
20 def mavset(self, mav, name, value, retries=3, parm_type=None):
21 '''set a parameter on a mavlink connection''' 24 if parm_type
is not None and parm_type != mavutil.mavlink.MAV_PARAM_TYPE_REAL32:
26 if parm_type == mavutil.mavlink.MAV_PARAM_TYPE_UINT8:
27 vstr = struct.pack(
">xxxB",
int(value))
28 elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT8:
29 vstr = struct.pack(
">xxxb",
int(value))
30 elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_UINT16:
31 vstr = struct.pack(
">xxH",
int(value))
32 elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT16:
33 vstr = struct.pack(
">xxh",
int(value))
34 elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_UINT32:
35 vstr = struct.pack(
">I",
int(value))
36 elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT32:
37 vstr = struct.pack(
">i",
int(value))
39 print(
"can't send %s of type %u" % (name, parm_type))
41 vfloat, = struct.unpack(
">f", vstr)
45 while retries > 0
and not got_ack:
47 mav.param_set_send(name.upper(), vfloat, parm_type=parm_type)
49 while time.time() - tstart < 1:
50 ack = mav.recv_match(type=
'PARAM_VALUE', blocking=
False)
54 if str(name).upper() ==
str(ack.param_id).upper():
56 self.__setitem__(name,
float(value))
59 print(
"timeout setting %s to %f" % (name, vfloat))
64 def save(self, filename, wildcard='*', verbose=False):
65 '''save parameters to a file''' 66 f = open(filename, mode=
'w')
71 if p
and fnmatch.fnmatch(
str(p).upper(), wildcard.upper()):
72 value = self.__getitem__(p)
73 if isinstance(value, float):
74 f.write(
"%-16.16s %f\n" % (p, value))
76 f.write(
"%-16.16s %s\n" % (p,
str(value)))
80 print(
"Saved %u parameters to %s" % (count, filename))
83 def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True):
84 '''load parameters from a file''' 86 f = open(filename, mode=
'r') 87 except Exception
as e:
88 print(
"Failed to open file '%s': %s" % (filename,
str(e)))
94 if not line
or line[0] ==
"#":
96 line = line.replace(
',',
' ')
99 print(
"Invalid line: %s" % line)
104 if not fnmatch.fnmatch(a[0].upper(), wildcard.upper()):
108 if a[0]
not in list(self.keys()):
109 print(
"Unknown parameter %s" % a[0])
111 old_value = self.__getitem__(a[0])
115 if self.
mavset(mav, a[0], a[1]):
116 print(
"changed %s from %f to %f" % (a[0], old_value,
float(a[1])))
118 print(
"set %s to %f" % (a[0],
float(a[1])))
119 self.
mavset(mav, a[0], a[1])
122 self.__setitem__(a[0],
float(a[1]))
126 print(
"Loaded %u parameters from %s (changed %u)" % (count, filename, changed))
128 print(
"Loaded %u parameters from %s" % (count, filename))
132 print(
"%-16.16s %s" % (name, value))
135 '''show parameters''' 136 k = sorted(self.keys())
138 if fnmatch.fnmatch(
str(p).upper(), wildcard.upper()):
141 def diff(self, filename, wildcard='*', use_excludes=True):
142 '''show differences with another parameter file''' 144 if not other.load(filename, use_excludes=use_excludes):
146 keys = sorted(list(set(self.keys()).union(set(other.keys()))))
148 if not fnmatch.fnmatch(
str(k).upper(), wildcard.upper()):
151 value =
float(self[k])
152 print(
"%-16.16s %12.4f" % (k, value))
154 print(
"%-16.16s %12.4f" % (k,
float(other[k])))
155 elif abs(self[k] - other[k]) > self.
mindelta:
156 value =
float(self[k])
157 print(
"%-16.16s %12.4f %12.4f" % (k, other[k], value))
def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True)
def save(self, filename, wildcard='*', verbose=False)
def diff(self, filename, wildcard='*', use_excludes=True)
def show_param_value(self, name, value)
def mavset(self, mav, name, value, retries=3, parm_type=None)
def show(self, wildcard='*')