Skip to content

Commit

Permalink
Mavgen WLua: Handle multiplier attribute in XML parser
Browse files Browse the repository at this point in the history
Mavparse: Handle attribute and store it in the internal classes

Mavgen WLua: Handle multiplier when displaying in Wireshark
Add a test case to demonstrate the behaviour
Remove unused uses of mavlink_type in Python code
  • Loading branch information
shancock884 authored and peterbarker committed May 29, 2024
1 parent 9606dbc commit 988c696
Show file tree
Hide file tree
Showing 6 changed files with 63 additions and 8 deletions.
18 changes: 16 additions & 2 deletions generator/mavgen_wlua.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,12 @@ def get_field_info(field):
field_type = "ftypes." + mavlink_type.upper()
tvb_func = "le_" + mavlink_type

# If a multiplier is defined, then add this to the displayed mavlink type
# and set the field type to DOUBLE to ensure that the full number is shown
if field.multiplier != "":
mavlink_type = mavlink_type + "*" + field.multiplier
field_type = "ftypes.DOUBLE"

return mavlink_type, field_type, tvb_func, size, count


Expand Down Expand Up @@ -222,7 +228,7 @@ def generate_msg_fields(outf, msg, enums):
index_text = ''

name = t.substitute("${fmsg}_${fname}${findex}", {'fmsg':msg.name, 'fname':f.name, 'findex':index_text})
label = t.substitute("${fname}${farray}", {'fname':f.name, 'farray':array_text, 'ftypename': mavlink_type})
label = t.substitute("${fname}${farray}", {'fname':f.name, 'farray':array_text})
generate_field_or_param(outf, f, name, label, mavlink_type, field_type, enums)

t.write(outf, '\n\n')
Expand Down Expand Up @@ -287,7 +293,7 @@ def generate_field_dissector(outf, msg, field, offset, enums, cmd=None, param=No
assert cmd is None or isinstance(cmd, mavparse.MAVEnumEntry)
assert param is None or isinstance(param, mavparse.MAVEnumParam)

mavlink_type, _, tvb_func, size, count = get_field_info(field)
_, _, tvb_func, size, count = get_field_info(field)

enum_name = param.enum if param else field.enum
enum_obj = enum_name and next((e for e in enums if e.name == enum_name), None)
Expand Down Expand Up @@ -319,6 +325,14 @@ def generate_field_dissector(outf, msg, field, offset, enums, cmd=None, param=No
value = tvbrange:${ftvbfunc}()
subtree = tree:add_le(f.${fvar}, tvbrange, value)
""", {'foffset': offset + i * size, 'fbytes': size, 'ftvbfunc': tvb_func, 'fvar': field_var})
elif field.multiplier != "":
value_extracted = True
t.write(outf,
"""
tvbrange = padded(offset + ${foffset}, ${fbytes})
value = tvbrange:${ftvbfunc}() * ${mult}
subtree = tree:add_le(f.${fvar}, tvbrange, value)
""", {'foffset': offset + i * size, 'fbytes': size, 'ftvbfunc': tvb_func, 'fvar': field_var, 'mult': field.multiplier})
else:
value_extracted = False
t.write(outf,
Expand Down
11 changes: 7 additions & 4 deletions generator/mavparse.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,15 @@ def __str__(self):
return self.message

class MAVField(object):
def __init__(self, name, type, print_format, xml, description='', enum='', display='', units='', instance=False):
def __init__(self, name, type, print_format, xml, description='', enum='', display='', units='', multiplier='', instance=False):
self.name = name
self.name_upper = name.upper()
self.description = description
self.array_length = 0
self.enum = enum
self.display = display
self.units = units
self.multiplier = multiplier
self.omit_arg = False
self.const_value = None
self.print_format = print_format
Expand Down Expand Up @@ -141,7 +142,7 @@ def base_fields(self):
return len(self.fields[:self.extensions_start])

class MAVEnumParam(object):
def __init__(self, index, description='', label='', units='', enum='', increment='', minValue='', maxValue='', reserved=False, default=''):
def __init__(self, index, description='', label='', units='', enum='', increment='', minValue='', maxValue='', reserved=False, default='', multiplier=''):
self.index = index
self.description = description
self.label = label
Expand All @@ -152,6 +153,7 @@ def __init__(self, index, description='', label='', units='', enum='', increment
self.maxValue = maxValue
self.reserved = reserved
self.default = default
self.multiplier = multiplier
if self.reserved and not self.default:
self.default = '0'
self.set_description(description)
Expand Down Expand Up @@ -256,8 +258,9 @@ def start_element(name, attrs):
units = attrs.get('units', '')
if units:
units = '[' + units + ']'
multiplier = attrs.get('multiplier', '')
instance = attrs.get('instance', False)
new_field = MAVField(attrs['name'], attrs['type'], print_format, self, enum=enum, display=display, units=units, instance=instance)
new_field = MAVField(attrs['name'], attrs['type'], print_format, self, enum=enum, display=display, units=units, multiplier=multiplier, instance=instance)
if self.message[-1].extensions_start is None or self.allow_extensions:
self.message[-1].fields.append(new_field)
elif in_element == "mavlink.enums.enum":
Expand Down Expand Up @@ -296,7 +299,7 @@ def start_element(name, attrs):
enum=attrs.get('enum', ''), increment=attrs.get('increment', ''),
minValue=attrs.get('minValue', ''),
maxValue=attrs.get('maxValue', ''), default=attrs.get('default', '0'),
reserved=attrs.get('reserved', False) ))
reserved=attrs.get('reserved', False), multiplier=attrs.get('multiplier','') ))

def is_target_system_field(m, f):
if f.name == 'target_system':
Expand Down
36 changes: 36 additions & 0 deletions tests/snapshottests/__snapshots__/test_wlua.ambr
Original file line number Diff line number Diff line change
Expand Up @@ -530,6 +530,42 @@
Message CRC: 0x4bdc


''',
})
# ---
# name: test_wlua[common.xml-gps_raw_int.pcapng]
dict({
'returncode': 0,
'stderr': '',
'stdout': '''
Frame 1: 97 bytes on wire (776 bits), 97 bytes captured (776 bits) on in
Ethernet II, Src: 00:00:00:00:00:00, Dst: 00:00:00:00:00:00
Internet Protocol Version 4, Src: 127.0.0.1, Dst: 127.0.0.1
User Datagram Protocol, Src Port: 52752, Dst Port: 14550
MAVLink Protocol (55)
Header
Magic value / version: MAVLink 2.0 (0xfd)
Payload length: 43
Incompatibility flag: 0x00 (0)
Compatibility flag: 0x00 (0)
Packet sequence: 58
System id: 1
Component id: MAV_COMP_ID_AUTOPILOT1 (1)
Message id: GPS_RAW_INT (24)
Payload: GPS_RAW_INT (24)
time_usec (uint64_t) [us]: 1583721000 (1583.721000 s)
fix_type (GPS_FIX_TYPE): GPS_FIX_TYPE_3D_FIX (3)
lat (int32_t) [degE7]: 514783466 (51.4783466 deg)
lon (int32_t) [degE7]: -25922214 (-2.5922214 deg)
alt (int32_t) [mm]: 56900
eph (uint16_t*1E-2): 2.33
epv (uint16_t*1E-2): 1.78
vel (uint16_t) [cm/s]: 0
cog (uint16_t) [cdeg]: 0
satellites_visible (uint8_t): 16
Message CRC: 0x1911


''',
})
# ---
4 changes: 2 additions & 2 deletions tests/snapshottests/resources/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5042,8 +5042,8 @@
<field type="int32_t" name="lat" units="degE7">Latitude (WGS84, EGM96 ellipsoid)</field>
<field type="int32_t" name="lon" units="degE7">Longitude (WGS84, EGM96 ellipsoid)</field>
<field type="int32_t" name="alt" units="mm">Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.</field>
<field type="uint16_t" name="eph" invalid="UINT16_MAX">GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="epv" invalid="UINT16_MAX">GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="eph" invalid="UINT16_MAX" multiplier="1E-2">GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="epv" invalid="UINT16_MAX" multiplier="1E-2">GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="vel" units="cm/s" invalid="UINT16_MAX">GPS ground speed. If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="cog" units="cdeg" invalid="UINT16_MAX">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX</field>
<field type="uint8_t" name="satellites_visible" invalid="UINT8_MAX">Number of satellites visible. If unknown, set to UINT8_MAX</field>
Expand Down
Binary file added tests/snapshottests/resources/gps_raw_int.pcapng
Binary file not shown.
2 changes: 2 additions & 0 deletions tests/snapshottests/test_wlua.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,8 @@ def snapshot(*args, **kwargs):
("common.xml", "gps_global_origin.pcapng"),
# test command specific params in MISSION_ITEM_INT are shown
("common.xml", "mission_item_int.pcapng"),
# test multipliers on eph and epv params of GPS_RAW_INT are handled
("common.xml", "gps_raw_int.pcapng"),
],
)
def test_wlua(request, tmp_path, snapshot, mdef, pcap):
Expand Down

0 comments on commit 988c696

Please sign in to comment.