This repository has been archived by the owner on May 14, 2024. It is now read-only.
forked from ArduPilot/pymavlink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mavparm.py
181 lines (166 loc) · 6.87 KB
/
mavparm.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
'''
module for loading/saving sets of mavlink parameters
'''
from __future__ import print_function
import fnmatch, math, time, struct
from pymavlink import mavutil
class MAVParmDict(dict):
def __init__(self, *args):
dict.__init__(self, args)
# some parameters should not be loaded from files
self.exclude_load = [
'ARSPD_OFFSET',
'CMD_INDEX',
'CMD_TOTAL',
'FENCE_TOTAL',
'FORMAT_VERSION',
'GND_ABS_PRESS',
'GND_TEMP',
'LOG_LASTFILE',
'MIS_TOTAL',
'SYSID_SW_MREV',
'SYS_NUM_RESETS',
]
self.mindelta = 0.000001
def mavset(self, mav, name, value, retries=3, parm_type=None):
'''set a parameter on a mavlink connection'''
got_ack = False
if parm_type is not None and parm_type != mavutil.mavlink.MAV_PARAM_TYPE_REAL32:
# need to encode as a float for sending
if parm_type == mavutil.mavlink.MAV_PARAM_TYPE_UINT8:
vstr = struct.pack(">xxxB", int(value))
elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT8:
vstr = struct.pack(">xxxb", int(value))
elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_UINT16:
vstr = struct.pack(">xxH", int(value))
elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT16:
vstr = struct.pack(">xxh", int(value))
elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_UINT32:
vstr = struct.pack(">I", int(value))
elif parm_type == mavutil.mavlink.MAV_PARAM_TYPE_INT32:
vstr = struct.pack(">i", int(value))
else:
print("can't send %s of type %u" % (name, parm_type))
return False
numeric_value, = struct.unpack(">f", vstr)
else:
if isinstance(value, str) and value.lower().startswith('0x'):
numeric_value = int(value[2:], 16)
else:
numeric_value = float(value)
while retries > 0 and not got_ack:
retries -= 1
mav.param_set_send(name.upper(), numeric_value, parm_type=parm_type)
tstart = time.time()
while time.time() - tstart < 1:
ack = mav.recv_match(type='PARAM_VALUE', blocking=False)
if ack is None:
time.sleep(0.1)
continue
if str(name).upper() == str(ack.param_id).upper():
got_ack = True
self.__setitem__(name, numeric_value)
break
if not got_ack:
print("timeout setting %s to %f" % (name, numeric_value))
return False
return True
def save(self, filename, wildcard='*', verbose=False):
'''save parameters to a file'''
f = open(filename, mode='w')
k = list(self.keys())
k.sort()
count = 0
for p in k:
if p and fnmatch.fnmatch(str(p).upper(), wildcard.upper()):
value = self.__getitem__(p)
if isinstance(value, float):
f.write("%-16.16s %f\n" % (p, value))
else:
f.write("%-16.16s %s\n" % (p, str(value)))
count += 1
f.close()
if verbose:
print("Saved %u parameters to %s" % (count, filename))
def load(self, filename, wildcard='*', mav=None, check=True, use_excludes=True):
'''load parameters from a file'''
try:
f = open(filename, mode='r')
except Exception as e:
print("Failed to open file '%s': %s" % (filename, str(e)))
return False
count = 0
changed = 0
for line in f:
line = line.strip()
if not line or line[0] == "#":
continue
line = line.replace(',',' ')
a = line.split()
if len(a) != 2:
print("Invalid line: %s" % line)
continue
# some parameters should not be loaded from files
if use_excludes and a[0] in self.exclude_load:
continue
if not fnmatch.fnmatch(a[0].upper(), wildcard.upper()):
continue
value = a[1].strip()
if isinstance(value, str) and value.lower().startswith('0x'):
numeric_value = int(value[2:], 16)
else:
numeric_value = float(value)
if mav is not None:
if check:
if a[0] not in list(self.keys()):
print("Unknown parameter %s" % a[0])
continue
old_value = self.__getitem__(a[0])
if math.fabs(old_value - numeric_value) <= self.mindelta:
count += 1
continue
if self.mavset(mav, a[0], value):
print("changed %s from %f to %f" % (a[0], old_value, numeric_value))
else:
print("set %s to %f" % (a[0], numeric_value))
self.mavset(mav, a[0], value)
changed += 1
else:
self.__setitem__(a[0], numeric_value)
count += 1
f.close()
if mav is not None:
print("Loaded %u parameters from %s (changed %u)" % (count, filename, changed))
else:
print("Loaded %u parameters from %s" % (count, filename))
return True
def show_param_value(self, name, value):
print("%-16.16s %s" % (name, value))
def show(self, wildcard='*'):
'''show parameters'''
k = sorted(self.keys())
for p in k:
if fnmatch.fnmatch(str(p).upper(), wildcard.upper()):
self.show_param_value(str(p), "%f" % self.get(p))
def diff(self, filename, wildcard='*', use_excludes=True, use_tabs=False, show_only1=True, show_only2=True):
'''show differences with another parameter file'''
other = MAVParmDict()
if not other.load(filename, use_excludes=use_excludes):
return
keys = sorted(list(set(self.keys()).union(set(other.keys()))))
for k in keys:
if not fnmatch.fnmatch(str(k).upper(), wildcard.upper()):
continue
if not k in other:
value = float(self[k])
if show_only2:
print("%-16.16s %12.4f" % (k, value))
elif not k in self:
if show_only1:
print("%-16.16s %12.4f" % (k, float(other[k])))
elif abs(self[k] - other[k]) > self.mindelta:
value = float(self[k])
if use_tabs:
print("%s\t%.4f\t%.4f" % (k, other[k], value))
else:
print("%-16.16s %12.4f %12.4f" % (k, other[k], value))