diff --git a/generator/mavgen_wlua.py b/generator/mavgen_wlua.py index 9f200e38a..6ccbdbb60 100644 --- a/generator/mavgen_wlua.py +++ b/generator/mavgen_wlua.py @@ -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 @@ -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') @@ -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) @@ -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, diff --git a/generator/mavparse.py b/generator/mavparse.py index 444793b0b..f15c77292 100644 --- a/generator/mavparse.py +++ b/generator/mavparse.py @@ -33,7 +33,7 @@ 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 @@ -41,6 +41,7 @@ def __init__(self, name, type, print_format, xml, description='', enum='', displ 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 @@ -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 @@ -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) @@ -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": @@ -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': diff --git a/tests/snapshottests/__snapshots__/test_wlua.ambr b/tests/snapshottests/__snapshots__/test_wlua.ambr index c981d5d0a..c46a2868d 100644 --- a/tests/snapshottests/__snapshots__/test_wlua.ambr +++ b/tests/snapshottests/__snapshots__/test_wlua.ambr @@ -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 + + ''', }) # --- diff --git a/tests/snapshottests/resources/common.xml b/tests/snapshottests/resources/common.xml index cb4584c12..114478776 100644 --- a/tests/snapshottests/resources/common.xml +++ b/tests/snapshottests/resources/common.xml @@ -5042,8 +5042,8 @@ Latitude (WGS84, EGM96 ellipsoid) Longitude (WGS84, EGM96 ellipsoid) Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. - GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX + GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX GPS ground speed. If unknown, set to: 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 Number of satellites visible. If unknown, set to UINT8_MAX diff --git a/tests/snapshottests/resources/gps_raw_int.pcapng b/tests/snapshottests/resources/gps_raw_int.pcapng new file mode 100644 index 000000000..e7d35fa5c Binary files /dev/null and b/tests/snapshottests/resources/gps_raw_int.pcapng differ diff --git a/tests/snapshottests/test_wlua.py b/tests/snapshottests/test_wlua.py index 310f09ad1..d28963be5 100644 --- a/tests/snapshottests/test_wlua.py +++ b/tests/snapshottests/test_wlua.py @@ -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):