From f74e47d07cb573e6e1003d48e79e29e6566b6dae Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Sat, 15 Jul 2023 16:37:49 +1000 Subject: [PATCH] Mavlink: update --- ExtLibs/Mavlink/Mavlink.cs | 520 +- ExtLibs/Mavlink/mavlink.lua | 59665 +++++++++------- .../message_definitions/ardupilotmega.xml | 10 + .../Mavlink/message_definitions/common.xml | 214 +- .../pymavlink/generator/mavgen_wlua.py | 225 +- 5 files changed, 36228 insertions(+), 24406 deletions(-) diff --git a/ExtLibs/Mavlink/Mavlink.cs b/ExtLibs/Mavlink/Mavlink.cs index db89473037..c3888f71f6 100644 --- a/ExtLibs/Mavlink/Mavlink.cs +++ b/ExtLibs/Mavlink/Mavlink.cs @@ -5,7 +5,7 @@ public partial class MAVLink { - public const string MAVLINK_BUILD_DATE = "Sun Apr 02 2023"; + public const string MAVLINK_BUILD_DATE = "Sat Jul 15 2023"; public const string MAVLINK_WIRE_PROTOCOL_VERSION = "2.0"; public const int MAVLINK_MAX_PAYLOAD_LEN = 255; @@ -66,7 +66,7 @@ public partial class MAVLink new message_info(39, "MISSION_ITEM", 254, 37, 38, typeof( mavlink_mission_item_t )), new message_info(40, "MISSION_REQUEST", 230, 4, 5, typeof( mavlink_mission_request_t )), new message_info(41, "MISSION_SET_CURRENT", 28, 4, 4, typeof( mavlink_mission_set_current_t )), - new message_info(42, "MISSION_CURRENT", 28, 2, 2, typeof( mavlink_mission_current_t )), + new message_info(42, "MISSION_CURRENT", 28, 2, 6, typeof( mavlink_mission_current_t )), new message_info(43, "MISSION_REQUEST_LIST", 132, 2, 3, typeof( mavlink_mission_request_list_t )), new message_info(44, "MISSION_COUNT", 221, 4, 5, typeof( mavlink_mission_count_t )), new message_info(45, "MISSION_CLEAR_ALL", 232, 2, 3, typeof( mavlink_mission_clear_all_t )), @@ -242,11 +242,14 @@ public partial class MAVLink new message_info(271, "CAMERA_FOV_STATUS", 22, 52, 52, typeof( mavlink_camera_fov_status_t )), new message_info(275, "CAMERA_TRACKING_IMAGE_STATUS", 126, 31, 31, typeof( mavlink_camera_tracking_image_status_t )), new message_info(276, "CAMERA_TRACKING_GEO_STATUS", 18, 49, 49, typeof( mavlink_camera_tracking_geo_status_t )), + new message_info(280, "GIMBAL_MANAGER_INFORMATION", 70, 33, 33, typeof( mavlink_gimbal_manager_information_t )), + new message_info(281, "GIMBAL_MANAGER_STATUS", 48, 13, 13, typeof( mavlink_gimbal_manager_status_t )), new message_info(282, "GIMBAL_MANAGER_SET_ATTITUDE", 123, 35, 35, typeof( mavlink_gimbal_manager_set_attitude_t )), new message_info(283, "GIMBAL_DEVICE_INFORMATION", 74, 144, 144, typeof( mavlink_gimbal_device_information_t )), new message_info(284, "GIMBAL_DEVICE_SET_ATTITUDE", 99, 32, 32, typeof( mavlink_gimbal_device_set_attitude_t )), new message_info(285, "GIMBAL_DEVICE_ATTITUDE_STATUS", 137, 40, 40, typeof( mavlink_gimbal_device_attitude_status_t )), new message_info(286, "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 210, 53, 53, typeof( mavlink_autopilot_state_for_gimbal_device_t )), + new message_info(287, "GIMBAL_MANAGER_SET_PITCHYAW", 1, 23, 23, typeof( mavlink_gimbal_manager_set_pitchyaw_t )), new message_info(299, "WIFI_CONFIG_AP", 19, 96, 96, typeof( mavlink_wifi_config_ap_t )), new message_info(301, "AIS_VESSEL", 243, 58, 58, typeof( mavlink_ais_vessel_t )), new message_info(310, "UAVCAN_NODE_STATUS", 28, 17, 17, typeof( mavlink_uavcan_node_status_t )), @@ -257,7 +260,7 @@ public partial class MAVLink new message_info(323, "PARAM_EXT_SET", 78, 147, 147, typeof( mavlink_param_ext_set_t )), new message_info(324, "PARAM_EXT_ACK", 132, 146, 146, typeof( mavlink_param_ext_ack_t )), new message_info(330, "OBSTACLE_DISTANCE", 23, 158, 167, typeof( mavlink_obstacle_distance_t )), - new message_info(331, "ODOMETRY", 91, 230, 232, typeof( mavlink_odometry_t )), + new message_info(331, "ODOMETRY", 91, 230, 233, typeof( mavlink_odometry_t )), new message_info(335, "ISBD_LINK_STATUS", 225, 24, 24, typeof( mavlink_isbd_link_status_t )), new message_info(339, "RAW_RPM", 199, 5, 5, typeof( mavlink_raw_rpm_t )), new message_info(340, "UTM_GLOBAL_POSITION", 99, 70, 70, typeof( mavlink_utm_global_position_t )), @@ -564,11 +567,14 @@ public enum MAVLINK_MSG_ID CAMERA_FOV_STATUS = 271, CAMERA_TRACKING_IMAGE_STATUS = 275, CAMERA_TRACKING_GEO_STATUS = 276, + GIMBAL_MANAGER_INFORMATION = 280, + GIMBAL_MANAGER_STATUS = 281, GIMBAL_MANAGER_SET_ATTITUDE = 282, GIMBAL_DEVICE_INFORMATION = 283, GIMBAL_DEVICE_SET_ATTITUDE = 284, GIMBAL_DEVICE_ATTITUDE_STATUS = 285, AUTOPILOT_STATE_FOR_GIMBAL_DEVICE = 286, + GIMBAL_MANAGER_SET_PITCHYAW = 287, WIFI_CONFIG_AP = 299, AIS_VESSEL = 301, UAVCAN_NODE_STATUS = 310, @@ -1052,6 +1058,10 @@ public enum MAV_CMD: ushort [Description("High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager.")] [Obsolete] DO_GIMBAL_MANAGER_PITCHYAW=1000, + /// Gimbal configuration to set which sysid/compid is in primary and secondary control. |Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Reserved (default:0)| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| + [Description("Gimbal configuration to set which sysid/compid is in primary and secondary control.")] + [Obsolete] + DO_GIMBAL_MANAGER_CONFIGURE=1001, /// Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. |Reserved (Set to 0)| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| [Description("Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values.")] IMAGE_START_CAPTURE=2000, @@ -1301,6 +1311,10 @@ public enum MAV_CMD: ushort /// Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) |course-over-ground or raw vehicle heading.| Target heading.| Maximum centripetal accelearation, ie rate of change, toward new heading.| Empty| Empty| Empty| Empty| [Description("Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)")] GUIDED_CHANGE_HEADING=43002, + /// Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link. |Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy.| The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known.| estimated one standard deviation accuracy of the measurement. Set to NaN if not known.| Empty| Latitude| Longitude| Altitude, not used. Should be sent as NaN. May be supported in a future version of this message.| + [Description("Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link.")] + [hasLocation()] + EXTERNAL_POSITION_ESTIMATE=43003, }; @@ -2920,6 +2934,61 @@ public enum GIMBAL_DEVICE_CAP_FLAGS: ushort }; + /// Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags. + [Flags] + public enum GIMBAL_MANAGER_CAP_FLAGS: uint + { + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT.")] + HAS_RETRACT=1, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL.")] + HAS_NEUTRAL=2, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS.")] + HAS_ROLL_AXIS=4, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW.")] + HAS_ROLL_FOLLOW=8, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK.")] + HAS_ROLL_LOCK=16, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS.")] + HAS_PITCH_AXIS=32, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW.")] + HAS_PITCH_FOLLOW=64, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK.")] + HAS_PITCH_LOCK=128, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS.")] + HAS_YAW_AXIS=256, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW.")] + HAS_YAW_FOLLOW=512, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK.")] + HAS_YAW_LOCK=1024, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW.")] + SUPPORTS_INFINITE_YAW=2048, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME.")] + SUPPORTS_YAW_IN_EARTH_FRAME=4096, + /// Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS. | + [Description("Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS.")] + HAS_RC_INPUTS=8192, + /// Gimbal manager supports to point to a local position. | + [Description("Gimbal manager supports to point to a local position.")] + CAN_POINT_LOCATION_LOCAL=65536, + /// Gimbal manager supports to point to a global latitude, longitude, altitude position. | + [Description("Gimbal manager supports to point to a global latitude, longitude, altitude position.")] + CAN_POINT_LOCATION_GLOBAL=131072, + + }; + /// Flags for gimbal device (lower level) operation. [Flags] public enum GIMBAL_DEVICE_FLAGS: ushort @@ -3100,6 +3169,39 @@ public enum STORAGE_STATUS: byte }; + /// Flags to indicate the type of storage. + public enum STORAGE_TYPE: byte + { + /// Storage type is not known. | + [Description("Storage type is not known.")] + UNKNOWN=0, + /// Storage type is USB device. | + [Description("Storage type is USB device.")] + USB_STICK=1, + /// Storage type is SD card. | + [Description("Storage type is SD card.")] + SD=2, + /// Storage type is microSD card. | + [Description("Storage type is microSD card.")] + MICROSD=3, + /// Storage type is CFast. | + [Description("Storage type is CFast.")] + CF=4, + /// Storage type is CFexpress. | + [Description("Storage type is CFexpress.")] + CFE=5, + /// Storage type is XQD. | + [Description("Storage type is XQD.")] + XQD=6, + /// Storage type is HD mass storage type. | + [Description("Storage type is HD mass storage type.")] + HD=7, + /// Storage type is other, not listed type. | + [Description("Storage type is other, not listed type.")] + OTHER=254, + + }; + /// Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE. public enum AUTOTUNE_AXIS: int /*default*/ { @@ -3172,39 +3274,6 @@ public enum MAV_ROI: int /*default*/ }; - /// ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. - public enum MAV_CMD_ACK: int /*default*/ - { - /// Command / mission item is ok. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("Command / mission item is ok.")] - OK=0, - /// Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.")] - ERR_FAIL=1, - /// The system is refusing to accept this command from this source / communication partner. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("The system is refusing to accept this command from this source / communication partner.")] - ERR_ACCESS_DENIED=2, - /// Command or mission item is not supported, other commands would be accepted. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("Command or mission item is not supported, other commands would be accepted.")] - ERR_NOT_SUPPORTED=3, - /// The coordinate frame of this command / mission item is not supported. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("The coordinate frame of this command / mission item is not supported.")] - ERR_COORDINATE_FRAME_NOT_SUPPORTED=4, - /// The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.")] - ERR_COORDINATES_OUT_OF_RANGE=5, - /// The X or latitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("The X or latitude value is out of range.")] - ERR_X_LAT_OUT_OF_RANGE=6, - /// The Y or longitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("The Y or longitude value is out of range.")] - ERR_Y_LON_OUT_OF_RANGE=7, - /// The Z or altitude value is out of range. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| - [Description("The Z or altitude value is out of range.")] - ERR_Z_ALT_OUT_OF_RANGE=8, - - }; - /// Specifies the datatype of a MAVLink parameter. public enum MAV_PARAM_TYPE: byte { @@ -5652,6 +5721,30 @@ public enum NAV_VTOL_LAND_OPTIONS: int /*default*/ }; + /// States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles. + public enum MISSION_STATE: byte + { + /// The mission status reporting is not supported. | + [Description("The mission status reporting is not supported.")] + UNKNOWN=0, + /// No mission on the vehicle. | + [Description("No mission on the vehicle.")] + NO_MISSION=1, + /// Mission has not started. This is the case after a mission has uploaded but not yet started executing. | + [Description("Mission has not started. This is the case after a mission has uploaded but not yet started executing.")] + NOT_STARTED=2, + /// Mission is active, and will execute mission items when in auto mode. | + [Description("Mission is active, and will execute mission items when in auto mode.")] + ACTIVE=3, + /// Mission is paused when in auto mode. | + [Description("Mission is paused when in auto mode.")] + PAUSED=4, + /// Mission has executed all mission items. | + [Description("Mission has executed all mission items.")] + COMPLETE=5, + + }; + /// State flags for ADS-B transponder dynamic report public enum UAVIONIX_ADSB_OUT_DYNAMIC_STATE: ushort @@ -14480,24 +14573,30 @@ public static mavlink_mission_set_current_t PopulateXMLOrder(byte target_system, }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)] + /// extensions_start 1 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)] /// Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. public struct mavlink_mission_current_t { /// packet ordered constructor - public mavlink_mission_current_t(ushort seq) + public mavlink_mission_current_t(ushort seq,ushort total,/*MISSION_STATE*/byte mission_state,byte mission_mode) { this.seq = seq; + this.total = total; + this.mission_state = mission_state; + this.mission_mode = mission_mode; } /// packet xml order - public static mavlink_mission_current_t PopulateXMLOrder(ushort seq) + public static mavlink_mission_current_t PopulateXMLOrder(ushort seq,ushort total,/*MISSION_STATE*/byte mission_state,byte mission_mode) { var msg = new mavlink_mission_current_t(); msg.seq = seq; + msg.total = total; + msg.mission_state = mission_state; + msg.mission_mode = mission_mode; return msg; } @@ -14508,6 +14607,24 @@ public static mavlink_mission_current_t PopulateXMLOrder(ushort seq) [Description("Sequence")] //[FieldOffset(0)] public ushort seq; + + /// Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. + [Units("")] + [Description("Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.")] + //[FieldOffset(2)] + public ushort total; + + /// Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. MISSION_STATE + [Units("")] + [Description("Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.")] + //[FieldOffset(4)] + public /*MISSION_STATE*/byte mission_state; + + /// Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). + [Units("")] + [Description("Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).")] + //[FieldOffset(5)] + public byte mission_mode; }; @@ -22258,9 +22375,9 @@ public static mavlink_autopilot_version_t PopulateXMLOrder(/*MAV_PROTOCOL_CAPABI //[FieldOffset(24)] public uint os_sw_version; - /// HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt + /// HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt [Units("")] - [Description("HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt")] + [Description("HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt")] //[FieldOffset(28)] public uint board_version; @@ -24914,27 +25031,27 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by //[FieldOffset(0)] public uint time_boot_ms; - /// Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff) + /// Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. [Units("")] - [Description("Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)")] + [Description("Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.")] //[FieldOffset(4)] public uint firmware_version; - /// Focal length [mm] + /// Focal length. Use NaN if not known. [mm] [Units("[mm]")] - [Description("Focal length")] + [Description("Focal length. Use NaN if not known.")] //[FieldOffset(8)] public float focal_length; - /// Image sensor size horizontal [mm] + /// Image sensor size horizontal. Use NaN if not known. [mm] [Units("[mm]")] - [Description("Image sensor size horizontal")] + [Description("Image sensor size horizontal. Use NaN if not known.")] //[FieldOffset(12)] public float sensor_size_h; - /// Image sensor size vertical [mm] + /// Image sensor size vertical. Use NaN if not known. [mm] [Units("[mm]")] - [Description("Image sensor size vertical")] + [Description("Image sensor size vertical. Use NaN if not known.")] //[FieldOffset(16)] public float sensor_size_v; @@ -24944,21 +25061,21 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by //[FieldOffset(20)] public /*CAMERA_CAP_FLAGS*/uint flags; - /// Horizontal image resolution [pix] + /// Horizontal image resolution. Use 0 if not known. [pix] [Units("[pix]")] - [Description("Horizontal image resolution")] + [Description("Horizontal image resolution. Use 0 if not known.")] //[FieldOffset(24)] public ushort resolution_h; - /// Vertical image resolution [pix] + /// Vertical image resolution. Use 0 if not known. [pix] [Units("[pix]")] - [Description("Vertical image resolution")] + [Description("Vertical image resolution. Use 0 if not known.")] //[FieldOffset(26)] public ushort resolution_v; - /// Camera definition version (iteration) + /// Camera definition version (iteration). Use 0 if not known. [Units("")] - [Description("Camera definition version (iteration)")] + [Description("Camera definition version (iteration). Use 0 if not known.")] //[FieldOffset(28)] public ushort cam_definition_version; @@ -24976,15 +25093,15 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] public byte[] model_name; - /// Reserved for a lens ID + /// Reserved for a lens ID. Use 0 if not known. [Units("")] - [Description("Reserved for a lens ID")] + [Description("Reserved for a lens ID. Use 0 if not known.")] //[FieldOffset(94)] public byte lens_id; - /// Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). + /// Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. [Units("")] - [Description("Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol).")] + [Description("Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.")] //[FieldOffset(95)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=140)] public byte[] cam_definition_uri; @@ -25032,15 +25149,15 @@ public static mavlink_camera_settings_t PopulateXMLOrder(uint time_boot_ms,/*CAM //[FieldOffset(4)] public /*CAMERA_MODE*/byte mode_id; - /// Current zoom level (0.0 to 100.0, NaN if not known) + /// Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) [Units("")] - [Description("Current zoom level (0.0 to 100.0, NaN if not known)")] + [Description("Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)")] //[FieldOffset(5)] public float zoomLevel; - /// Current focus level (0.0 to 100.0, NaN if not known) + /// Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) [Units("")] - [Description("Current focus level (0.0 to 100.0, NaN if not known)")] + [Description("Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)")] //[FieldOffset(9)] public float focusLevel; }; @@ -26200,6 +26317,180 @@ public static mavlink_camera_tracking_geo_status_t PopulateXMLOrder(/*CAMERA_TRA public /*CAMERA_TRACKING_STATUS_FLAGS*/byte tracking_status; }; + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)] + /// Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. + public struct mavlink_gimbal_manager_information_t + { + /// packet ordered constructor + public mavlink_gimbal_manager_information_t(uint time_boot_ms,/*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,byte gimbal_device_id) + { + this.time_boot_ms = time_boot_ms; + this.cap_flags = cap_flags; + this.roll_min = roll_min; + this.roll_max = roll_max; + this.pitch_min = pitch_min; + this.pitch_max = pitch_max; + this.yaw_min = yaw_min; + this.yaw_max = yaw_max; + this.gimbal_device_id = gimbal_device_id; + + } + + /// packet xml order + public static mavlink_gimbal_manager_information_t PopulateXMLOrder(uint time_boot_ms,/*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags,byte gimbal_device_id,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) + { + var msg = new mavlink_gimbal_manager_information_t(); + + msg.time_boot_ms = time_boot_ms; + msg.cap_flags = cap_flags; + msg.gimbal_device_id = gimbal_device_id; + msg.roll_min = roll_min; + msg.roll_max = roll_max; + msg.pitch_min = pitch_min; + msg.pitch_max = pitch_max; + msg.yaw_min = yaw_min; + msg.yaw_max = yaw_max; + + return msg; + } + + + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; + + /// Bitmap of gimbal capability flags. GIMBAL_MANAGER_CAP_FLAGS bitmask + [Units("")] + [Description("Bitmap of gimbal capability flags.")] + //[FieldOffset(4)] + public /*GIMBAL_MANAGER_CAP_FLAGS*/uint cap_flags; + + /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + [Units("[rad]")] + [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] + //[FieldOffset(8)] + public float roll_min; + + /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + [Units("[rad]")] + [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] + //[FieldOffset(12)] + public float roll_max; + + /// Minimum pitch angle (positive: up, negative: down) [rad] + [Units("[rad]")] + [Description("Minimum pitch angle (positive: up, negative: down)")] + //[FieldOffset(16)] + public float pitch_min; + + /// Maximum pitch angle (positive: up, negative: down) [rad] + [Units("[rad]")] + [Description("Maximum pitch angle (positive: up, negative: down)")] + //[FieldOffset(20)] + public float pitch_max; + + /// Minimum yaw angle (positive: to the right, negative: to the left) [rad] + [Units("[rad]")] + [Description("Minimum yaw angle (positive: to the right, negative: to the left)")] + //[FieldOffset(24)] + public float yaw_min; + + /// Maximum yaw angle (positive: to the right, negative: to the left) [rad] + [Units("[rad]")] + [Description("Maximum yaw angle (positive: to the right, negative: to the left)")] + //[FieldOffset(28)] + public float yaw_max; + + /// Gimbal device ID that this gimbal manager is responsible for. + [Units("")] + [Description("Gimbal device ID that this gimbal manager is responsible for.")] + //[FieldOffset(32)] + public byte gimbal_device_id; + }; + + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)] + /// Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz). + public struct mavlink_gimbal_manager_status_t + { + /// packet ordered constructor + public mavlink_gimbal_manager_status_t(uint time_boot_ms,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,byte primary_control_sysid,byte primary_control_compid,byte secondary_control_sysid,byte secondary_control_compid) + { + this.time_boot_ms = time_boot_ms; + this.flags = flags; + this.gimbal_device_id = gimbal_device_id; + this.primary_control_sysid = primary_control_sysid; + this.primary_control_compid = primary_control_compid; + this.secondary_control_sysid = secondary_control_sysid; + this.secondary_control_compid = secondary_control_compid; + + } + + /// packet xml order + public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,byte primary_control_sysid,byte primary_control_compid,byte secondary_control_sysid,byte secondary_control_compid) + { + var msg = new mavlink_gimbal_manager_status_t(); + + msg.time_boot_ms = time_boot_ms; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.primary_control_sysid = primary_control_sysid; + msg.primary_control_compid = primary_control_compid; + msg.secondary_control_sysid = secondary_control_sysid; + msg.secondary_control_compid = secondary_control_compid; + + return msg; + } + + + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; + + /// High level gimbal manager flags currently applied. GIMBAL_MANAGER_FLAGS + [Units("")] + [Description("High level gimbal manager flags currently applied.")] + //[FieldOffset(4)] + public /*GIMBAL_MANAGER_FLAGS*/uint flags; + + /// Gimbal device ID that this gimbal manager is responsible for. + [Units("")] + [Description("Gimbal device ID that this gimbal manager is responsible for.")] + //[FieldOffset(8)] + public byte gimbal_device_id; + + /// System ID of MAVLink component with primary control, 0 for none. + [Units("")] + [Description("System ID of MAVLink component with primary control, 0 for none.")] + //[FieldOffset(9)] + public byte primary_control_sysid; + + /// Component ID of MAVLink component with primary control, 0 for none. + [Units("")] + [Description("Component ID of MAVLink component with primary control, 0 for none.")] + //[FieldOffset(10)] + public byte primary_control_compid; + + /// System ID of MAVLink component with secondary control, 0 for none. + [Units("")] + [Description("System ID of MAVLink component with secondary control, 0 for none.")] + //[FieldOffset(11)] + public byte secondary_control_sysid; + + /// Component ID of MAVLink component with secondary control, 0 for none. + [Units("")] + [Description("Component ID of MAVLink component with secondary control, 0 for none.")] + //[FieldOffset(12)] + public byte secondary_control_compid; + }; + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=144)] @@ -26730,6 +27021,93 @@ public static mavlink_gimbal_manager_set_attitude_t PopulateXMLOrder(byte target public byte gimbal_device_id; }; + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] + /// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + public struct mavlink_gimbal_manager_set_pitchyaw_t + { + /// packet ordered constructor + public mavlink_gimbal_manager_set_pitchyaw_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float pitch,float yaw,float pitch_rate,float yaw_rate,byte target_system,byte target_component,byte gimbal_device_id) + { + this.flags = flags; + this.pitch = pitch; + this.yaw = yaw; + this.pitch_rate = pitch_rate; + this.yaw_rate = yaw_rate; + this.target_system = target_system; + this.target_component = target_component; + this.gimbal_device_id = gimbal_device_id; + + } + + /// packet xml order + public static mavlink_gimbal_manager_set_pitchyaw_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate) + { + var msg = new mavlink_gimbal_manager_set_pitchyaw_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.pitch = pitch; + msg.yaw = yaw; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; + + return msg; + } + + + /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS + [Units("")] + [Description("High level gimbal manager flags to use.")] + //[FieldOffset(0)] + public /*GIMBAL_MANAGER_FLAGS*/uint flags; + + /// Pitch angle (positive: up, negative: down, NaN to be ignored). [rad] + [Units("[rad]")] + [Description("Pitch angle (positive: up, negative: down, NaN to be ignored).")] + //[FieldOffset(4)] + public float pitch; + + /// Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). [rad] + [Units("[rad]")] + [Description("Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).")] + //[FieldOffset(8)] + public float yaw; + + /// Pitch angular rate (positive: up, negative: down, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Pitch angular rate (positive: up, negative: down, NaN to be ignored).")] + //[FieldOffset(12)] + public float pitch_rate; + + /// Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).")] + //[FieldOffset(16)] + public float yaw_rate; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(20)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(21)] + public byte target_component; + + /// Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + [Units("")] + [Description("Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).")] + //[FieldOffset(22)] + public byte gimbal_device_id; + }; + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=96)] @@ -27480,12 +27858,12 @@ public static mavlink_obstacle_distance_t PopulateXMLOrder(ulong time_usec,/*MAV /// extensions_start 15 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=232)] + [StructLayout(LayoutKind.Sequential,Pack=1,Size=233)] /// Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html). public struct mavlink_odometry_t { /// packet ordered constructor - public mavlink_odometry_t(ulong time_usec,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type) + public mavlink_odometry_t(ulong time_usec,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,sbyte quality) { this.time_usec = time_usec; this.x = x; @@ -27504,11 +27882,12 @@ public mavlink_odometry_t(ulong time_usec,float x,float y,float z,float[] q,floa this.child_frame_id = child_frame_id; this.reset_counter = reset_counter; this.estimator_type = estimator_type; + this.quality = quality; } /// packet xml order - public static mavlink_odometry_t PopulateXMLOrder(ulong time_usec,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type) + public static mavlink_odometry_t PopulateXMLOrder(ulong time_usec,/*MAV_FRAME*/byte frame_id,/*MAV_FRAME*/byte child_frame_id,float x,float y,float z,float[] q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,float[] pose_covariance,float[] velocity_covariance,byte reset_counter,/*MAV_ESTIMATOR_TYPE*/byte estimator_type,sbyte quality) { var msg = new mavlink_odometry_t(); @@ -27529,6 +27908,7 @@ public static mavlink_odometry_t PopulateXMLOrder(ulong time_usec,/*MAV_FRAME*/b msg.velocity_covariance = velocity_covariance; msg.reset_counter = reset_counter; msg.estimator_type = estimator_type; + msg.quality = quality; return msg; } @@ -27638,6 +28018,12 @@ public static mavlink_odometry_t PopulateXMLOrder(ulong time_usec,/*MAV_FRAME*/b [Description("Type of estimator that is providing the odometry.")] //[FieldOffset(231)] public /*MAV_ESTIMATOR_TYPE*/byte estimator_type; + + /// Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality [%] + [Units("[%]")] + [Description("Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality")] + //[FieldOffset(232)] + public sbyte quality; }; diff --git a/ExtLibs/Mavlink/mavlink.lua b/ExtLibs/Mavlink/mavlink.lua index 25749902b5..30017a3c44 100644 --- a/ExtLibs/Mavlink/mavlink.lua +++ b/ExtLibs/Mavlink/mavlink.lua @@ -1,7 +1,6 @@ -- Wireshark dissector for the MAVLink protocol (please see https://mavlink.io/en for details) unknownFrameBeginOffset = 0 -local bit = require "bit32" mavlink_proto = Proto("mavlink_proto", "MAVLink protocol") f = mavlink_proto.fields @@ -251,11 +250,14 @@ messageName = { [271] = 'CAMERA_FOV_STATUS', [275] = 'CAMERA_TRACKING_IMAGE_STATUS', [276] = 'CAMERA_TRACKING_GEO_STATUS', + [280] = 'GIMBAL_MANAGER_INFORMATION', + [281] = 'GIMBAL_MANAGER_STATUS', [283] = 'GIMBAL_DEVICE_INFORMATION', [284] = 'GIMBAL_DEVICE_SET_ATTITUDE', [285] = 'GIMBAL_DEVICE_ATTITUDE_STATUS', [286] = 'AUTOPILOT_STATE_FOR_GIMBAL_DEVICE', [282] = 'GIMBAL_MANAGER_SET_ATTITUDE', + [287] = 'GIMBAL_MANAGER_SET_PITCHYAW', [299] = 'WIFI_CONFIG_AP', [301] = 'AIS_VESSEL', [310] = 'UAVCAN_NODE_STATUS', @@ -309,7 +311,7 @@ messageName = { [0] = 'HEARTBEAT', } -enumEntryName = { +local enumEntryName = { ["ACCELCAL_VEHICLE_POS"] = { [1] = "ACCELCAL_VEHICLE_POS_LEVEL", [2] = "ACCELCAL_VEHICLE_POS_LEFT", @@ -434,6 +436,7 @@ enumEntryName = { [600] = "MAV_CMD_JUMP_TAG", [601] = "MAV_CMD_DO_JUMP_TAG", [1000] = "MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW", + [1001] = "MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE", [2000] = "MAV_CMD_IMAGE_START_CAPTURE", [2001] = "MAV_CMD_IMAGE_STOP_CAPTURE", [2003] = "MAV_CMD_DO_TRIGGER_CONTROL", @@ -510,6 +513,7 @@ enumEntryName = { [43000] = "MAV_CMD_GUIDED_CHANGE_SPEED", [43001] = "MAV_CMD_GUIDED_CHANGE_ALTITUDE", [43002] = "MAV_CMD_GUIDED_CHANGE_HEADING", + [43003] = "MAV_CMD_EXTERNAL_POSITION_ESTIMATE", }, ["SCRIPTING_CMD"] = { [0] = "SCRIPTING_CMD_REPL_START", @@ -1044,6 +1048,24 @@ enumEntryName = { [1024] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", [2048] = "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", }, + ["GIMBAL_MANAGER_CAP_FLAGS"] = { + [1] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT", + [2] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL", + [4] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS", + [8] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW", + [16] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK", + [32] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS", + [64] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW", + [128] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK", + [256] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS", + [512] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW", + [1024] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK", + [2048] = "GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW", + [4096] = "GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", + [8192] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS", + [65536] = "GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL", + [131072] = "GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL", + }, ["GIMBAL_DEVICE_FLAGS"] = { [1] = "GIMBAL_DEVICE_FLAGS_RETRACT", [2] = "GIMBAL_DEVICE_FLAGS_NEUTRAL", @@ -1103,6 +1125,17 @@ enumEntryName = { [2] = "STORAGE_STATUS_READY", [3] = "STORAGE_STATUS_NOT_SUPPORTED", }, + ["STORAGE_TYPE"] = { + [0] = "STORAGE_TYPE_UNKNOWN", + [1] = "STORAGE_TYPE_USB_STICK", + [2] = "STORAGE_TYPE_SD", + [3] = "STORAGE_TYPE_MICROSD", + [4] = "STORAGE_TYPE_CF", + [5] = "STORAGE_TYPE_CFE", + [6] = "STORAGE_TYPE_XQD", + [7] = "STORAGE_TYPE_HD", + [254] = "STORAGE_TYPE_OTHER", + }, ["AUTOTUNE_AXIS"] = { [0] = "AUTOTUNE_AXIS_DEFAULT", [1] = "AUTOTUNE_AXIS_ROLL", @@ -1127,17 +1160,6 @@ enumEntryName = { [3] = "MAV_ROI_LOCATION", [4] = "MAV_ROI_TARGET", }, - ["MAV_CMD_ACK"] = { - [0] = "MAV_CMD_ACK_OK", - [1] = "MAV_CMD_ACK_ERR_FAIL", - [2] = "MAV_CMD_ACK_ERR_ACCESS_DENIED", - [3] = "MAV_CMD_ACK_ERR_NOT_SUPPORTED", - [4] = "MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED", - [5] = "MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE", - [6] = "MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE", - [7] = "MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE", - [8] = "MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE", - }, ["MAV_PARAM_TYPE"] = { [1] = "MAV_PARAM_TYPE_UINT8", [2] = "MAV_PARAM_TYPE_INT8", @@ -1949,6 +1971,14 @@ enumEntryName = { [1] = "NAV_VTOL_LAND_OPTIONS_FW_SPIRAL_APPROACH", [2] = "NAV_VTOL_LAND_OPTIONS_FW_APPROACH", }, + ["MISSION_STATE"] = { + [0] = "MISSION_STATE_UNKNOWN", + [1] = "MISSION_STATE_NO_MISSION", + [2] = "MISSION_STATE_NOT_STARTED", + [3] = "MISSION_STATE_ACTIVE", + [4] = "MISSION_STATE_PAUSED", + [5] = "MISSION_STATE_COMPLETE", + }, ["UAVIONIX_ADSB_OUT_DYNAMIC_STATE"] = { [1] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", [2] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", @@ -2334,7 +2364,6 @@ f.signature_time = ProtoField.absolute_time("mavlink_proto.signature_time", "Tim f.signature_signature = ProtoField.bytes("mavlink_proto.signature_signature", "Signature") f.rawheader = ProtoField.bytes("mavlink_proto.rawheader", "Unparsable header fragment") f.rawpayload = ProtoField.bytes("mavlink_proto.rawpayload", "Unparsable payload") - f.cmd_MAV_CMD_NAV_WAYPOINT_param1 = ProtoField.new("param1: Hold (float)", "mavlink_proto.cmd_MAV_CMD_NAV_WAYPOINT_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_NAV_WAYPOINT_param2 = ProtoField.new("param2: Accept Radius (float)", "mavlink_proto.cmd_MAV_CMD_NAV_WAYPOINT_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_NAV_WAYPOINT_param3 = ProtoField.new("param3: Pass Radius (float)", "mavlink_proto.cmd_MAV_CMD_NAV_WAYPOINT_param3", ftypes.FLOAT, nil) @@ -2533,8 +2562,8 @@ f.cmd_MAV_CMD_DO_GO_AROUND_param1 = ProtoField.new("param1: Altitude (float)", " f.cmd_MAV_CMD_DO_REPOSITION_param1 = ProtoField.new("param1: Speed (float)", "mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_REPOSITION_param2 = ProtoField.new("param2: Bitmask (MAV_DO_REPOSITION_FLAGS)", "mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param2", ftypes.UINT32, nil) -f.cmd_MAV_CMD_DO_REPOSITION_param2_flagMAV_DO_REPOSITION_FLAGS_CHANGE_MODE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param2.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE", "MAV_DO_REPOSITION_FLAGS_CHANGE_MODE") -f.cmd_MAV_CMD_DO_REPOSITION_param2_flagMAV_DO_REPOSITION_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param2.MAV_DO_REPOSITION_FLAGS_ENUM_END", "MAV_DO_REPOSITION_FLAGS_ENUM_END") +f.cmd_MAV_CMD_DO_REPOSITION_param2_flagMAV_DO_REPOSITION_FLAGS_CHANGE_MODE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param2.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE", "MAV_DO_REPOSITION_FLAGS_CHANGE_MODE", 2, nil, 1) +f.cmd_MAV_CMD_DO_REPOSITION_param2_flagMAV_DO_REPOSITION_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param2.MAV_DO_REPOSITION_FLAGS_ENUM_END", "MAV_DO_REPOSITION_FLAGS_ENUM_END", 2, nil, 2) f.cmd_MAV_CMD_DO_REPOSITION_param3 = ProtoField.new("param3: Radius (float)", "mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param3", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_REPOSITION_param4 = ProtoField.new("param4: Yaw (float)", "mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param4", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_REPOSITION_param5 = ProtoField.new("param5: Latitude (float)", "mavlink_proto.cmd_MAV_CMD_DO_REPOSITION_param5", ftypes.FLOAT, nil) @@ -2609,7 +2638,10 @@ f.cmd_MAV_CMD_DO_GRIPPER_param1 = ProtoField.new("param1: Instance (float)", "ma f.cmd_MAV_CMD_DO_GRIPPER_param2 = ProtoField.new("param2: Action (GRIPPER_ACTIONS)", "mavlink_proto.cmd_MAV_CMD_DO_GRIPPER_param2", ftypes.UINT32, enumEntryName.GRIPPER_ACTIONS) f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1 = ProtoField.new("param1: Enable (float)", "mavlink_proto.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1", ftypes.FLOAT, nil) -f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2 = ProtoField.new("param2: Axis (AUTOTUNE_AXIS)", "mavlink_proto.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2", ftypes.UINT32, enumEntryName.AUTOTUNE_AXIS) +f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2 = ProtoField.new("param2: Axis (AUTOTUNE_AXIS)", "mavlink_proto.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2", ftypes.UINT32, nil) +f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2_flagAUTOTUNE_AXIS_ROLL = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2.AUTOTUNE_AXIS_ROLL", "AUTOTUNE_AXIS_ROLL", 3, nil, 1) +f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2_flagAUTOTUNE_AXIS_PITCH = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2.AUTOTUNE_AXIS_PITCH", "AUTOTUNE_AXIS_PITCH", 3, nil, 2) +f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2_flagAUTOTUNE_AXIS_YAW = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2.AUTOTUNE_AXIS_YAW", "AUTOTUNE_AXIS_YAW", 3, nil, 4) f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1 = ProtoField.new("param1: Yaw (float)", "mavlink_proto.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1", ftypes.FLOAT, nil) f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2 = ProtoField.new("param2: Speed (float)", "mavlink_proto.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2", ftypes.FLOAT, nil) @@ -2753,13 +2785,19 @@ f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2 = ProtoField.new("param2: Yaw an f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3 = ProtoField.new("param3: Pitch rate (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4 = ProtoField.new("param4: Yaw rate (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4", ftypes.FLOAT, nil) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5 = ProtoField.new("param5: Gimbal manager flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", ftypes.UINT32, nil) -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT") -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL") -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK") -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK") -f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK") +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7 = ProtoField.new("param7: Gimbal device ID (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1 = ProtoField.new("param1: sysid primary control (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param2 = ProtoField.new("param2: compid primary control (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param2", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param3 = ProtoField.new("param3: sysid secondary control (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4 = ProtoField.new("param4: compid secondary control (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7 = ProtoField.new("param7: Gimbal device ID (float)", "mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7", ftypes.FLOAT, nil) + f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2 = ProtoField.new("param2: Interval (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3 = ProtoField.new("param3: Total Images (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3", ftypes.FLOAT, nil) f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4 = ProtoField.new("param4: Sequence Number (float)", "mavlink_proto.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4", ftypes.FLOAT, nil) @@ -2980,6 +3018,13 @@ f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1 = ProtoField.new("param1: heading typ f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2 = ProtoField.new("param2: heading target (float)", "mavlink_proto.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2", ftypes.FLOAT, nil) f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3 = ProtoField.new("param3: heading rate-of-change (float)", "mavlink_proto.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1 = ProtoField.new("param1: transmission_time (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2 = ProtoField.new("param2: processing_time (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3 = ProtoField.new("param3: accuracy (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5 = ProtoField.new("param5: Latitude (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6 = ProtoField.new("param6: Longitude (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6", ftypes.FLOAT, nil) +f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7 = ProtoField.new("param7: Altitude (float)", "mavlink_proto.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7", ftypes.FLOAT, nil) + f.SENSOR_OFFSETS_mag_ofs_x = ProtoField.new("mag_ofs_x (int16_t)", "mavlink_proto.SENSOR_OFFSETS_mag_ofs_x", ftypes.INT16, nil) f.SENSOR_OFFSETS_mag_ofs_y = ProtoField.new("mag_ofs_y (int16_t)", "mavlink_proto.SENSOR_OFFSETS_mag_ofs_y", ftypes.INT16, nil) @@ -3104,17 +3149,17 @@ f.LIMITS_STATUS_last_recovery = ProtoField.new("last_recovery (uint32_t)", "mavl f.LIMITS_STATUS_last_clear = ProtoField.new("last_clear (uint32_t)", "mavlink_proto.LIMITS_STATUS_last_clear", ftypes.UINT32, nil) f.LIMITS_STATUS_breach_count = ProtoField.new("breach_count (uint16_t)", "mavlink_proto.LIMITS_STATUS_breach_count", ftypes.UINT16, nil) f.LIMITS_STATUS_mods_enabled = ProtoField.new("mods_enabled (LIMIT_MODULE)", "mavlink_proto.LIMITS_STATUS_mods_enabled", ftypes.UINT8, nil) -f.LIMITS_STATUS_mods_enabled_flagLIMIT_GPSLOCK = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_enabled.LIMIT_GPSLOCK", "LIMIT_GPSLOCK") -f.LIMITS_STATUS_mods_enabled_flagLIMIT_GEOFENCE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_enabled.LIMIT_GEOFENCE", "LIMIT_GEOFENCE") -f.LIMITS_STATUS_mods_enabled_flagLIMIT_ALTITUDE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_enabled.LIMIT_ALTITUDE", "LIMIT_ALTITUDE") +f.LIMITS_STATUS_mods_enabled_flagLIMIT_GPSLOCK = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_enabled.LIMIT_GPSLOCK", "LIMIT_GPSLOCK", 3, nil, 1) +f.LIMITS_STATUS_mods_enabled_flagLIMIT_GEOFENCE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_enabled.LIMIT_GEOFENCE", "LIMIT_GEOFENCE", 3, nil, 2) +f.LIMITS_STATUS_mods_enabled_flagLIMIT_ALTITUDE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_enabled.LIMIT_ALTITUDE", "LIMIT_ALTITUDE", 3, nil, 4) f.LIMITS_STATUS_mods_required = ProtoField.new("mods_required (LIMIT_MODULE)", "mavlink_proto.LIMITS_STATUS_mods_required", ftypes.UINT8, nil) -f.LIMITS_STATUS_mods_required_flagLIMIT_GPSLOCK = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_required.LIMIT_GPSLOCK", "LIMIT_GPSLOCK") -f.LIMITS_STATUS_mods_required_flagLIMIT_GEOFENCE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_required.LIMIT_GEOFENCE", "LIMIT_GEOFENCE") -f.LIMITS_STATUS_mods_required_flagLIMIT_ALTITUDE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_required.LIMIT_ALTITUDE", "LIMIT_ALTITUDE") +f.LIMITS_STATUS_mods_required_flagLIMIT_GPSLOCK = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_required.LIMIT_GPSLOCK", "LIMIT_GPSLOCK", 3, nil, 1) +f.LIMITS_STATUS_mods_required_flagLIMIT_GEOFENCE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_required.LIMIT_GEOFENCE", "LIMIT_GEOFENCE", 3, nil, 2) +f.LIMITS_STATUS_mods_required_flagLIMIT_ALTITUDE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_required.LIMIT_ALTITUDE", "LIMIT_ALTITUDE", 3, nil, 4) f.LIMITS_STATUS_mods_triggered = ProtoField.new("mods_triggered (LIMIT_MODULE)", "mavlink_proto.LIMITS_STATUS_mods_triggered", ftypes.UINT8, nil) -f.LIMITS_STATUS_mods_triggered_flagLIMIT_GPSLOCK = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_triggered.LIMIT_GPSLOCK", "LIMIT_GPSLOCK") -f.LIMITS_STATUS_mods_triggered_flagLIMIT_GEOFENCE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_triggered.LIMIT_GEOFENCE", "LIMIT_GEOFENCE") -f.LIMITS_STATUS_mods_triggered_flagLIMIT_ALTITUDE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_triggered.LIMIT_ALTITUDE", "LIMIT_ALTITUDE") +f.LIMITS_STATUS_mods_triggered_flagLIMIT_GPSLOCK = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_triggered.LIMIT_GPSLOCK", "LIMIT_GPSLOCK", 3, nil, 1) +f.LIMITS_STATUS_mods_triggered_flagLIMIT_GEOFENCE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_triggered.LIMIT_GEOFENCE", "LIMIT_GEOFENCE", 3, nil, 2) +f.LIMITS_STATUS_mods_triggered_flagLIMIT_ALTITUDE = ProtoField.bool("mavlink_proto.LIMITS_STATUS_mods_triggered.LIMIT_ALTITUDE", "LIMIT_ALTITUDE", 3, nil, 4) f.WIND_direction = ProtoField.new("direction (float)", "mavlink_proto.WIND_direction", ftypes.FLOAT, nil) f.WIND_speed = ProtoField.new("speed (float)", "mavlink_proto.WIND_speed", ftypes.FLOAT, nil) @@ -3366,8 +3411,8 @@ f.RALLY_POINT_alt = ProtoField.new("alt (int16_t)", "mavlink_proto.RALLY_POINT_a f.RALLY_POINT_break_alt = ProtoField.new("break_alt (int16_t)", "mavlink_proto.RALLY_POINT_break_alt", ftypes.INT16, nil) f.RALLY_POINT_land_dir = ProtoField.new("land_dir (uint16_t)", "mavlink_proto.RALLY_POINT_land_dir", ftypes.UINT16, nil) f.RALLY_POINT_flags = ProtoField.new("flags (RALLY_FLAGS)", "mavlink_proto.RALLY_POINT_flags", ftypes.UINT8, nil) -f.RALLY_POINT_flags_flagFAVORABLE_WIND = ProtoField.bool("mavlink_proto.RALLY_POINT_flags.FAVORABLE_WIND", "FAVORABLE_WIND") -f.RALLY_POINT_flags_flagLAND_IMMEDIATELY = ProtoField.bool("mavlink_proto.RALLY_POINT_flags.LAND_IMMEDIATELY", "LAND_IMMEDIATELY") +f.RALLY_POINT_flags_flagFAVORABLE_WIND = ProtoField.bool("mavlink_proto.RALLY_POINT_flags.FAVORABLE_WIND", "FAVORABLE_WIND", 2, nil, 1) +f.RALLY_POINT_flags_flagLAND_IMMEDIATELY = ProtoField.bool("mavlink_proto.RALLY_POINT_flags.LAND_IMMEDIATELY", "LAND_IMMEDIATELY", 2, nil, 2) f.RALLY_FETCH_POINT_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.RALLY_FETCH_POINT_target_system", ftypes.UINT8, nil) f.RALLY_FETCH_POINT_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.RALLY_FETCH_POINT_target_component", ftypes.UINT8, nil) @@ -3688,17 +3733,17 @@ f.MAG_CAL_PROGRESS_direction_y = ProtoField.new("direction_y (float)", "mavlink_ f.MAG_CAL_PROGRESS_direction_z = ProtoField.new("direction_z (float)", "mavlink_proto.MAG_CAL_PROGRESS_direction_z", ftypes.FLOAT, nil) f.EKF_STATUS_REPORT_flags = ProtoField.new("flags (EKF_STATUS_FLAGS)", "mavlink_proto.EKF_STATUS_REPORT_flags", ftypes.UINT16, nil) -f.EKF_STATUS_REPORT_flags_flagEKF_ATTITUDE = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_ATTITUDE", "EKF_ATTITUDE") -f.EKF_STATUS_REPORT_flags_flagEKF_VELOCITY_HORIZ = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_VELOCITY_HORIZ", "EKF_VELOCITY_HORIZ") -f.EKF_STATUS_REPORT_flags_flagEKF_VELOCITY_VERT = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_VELOCITY_VERT", "EKF_VELOCITY_VERT") -f.EKF_STATUS_REPORT_flags_flagEKF_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_HORIZ_REL", "EKF_POS_HORIZ_REL") -f.EKF_STATUS_REPORT_flags_flagEKF_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_HORIZ_ABS", "EKF_POS_HORIZ_ABS") -f.EKF_STATUS_REPORT_flags_flagEKF_POS_VERT_ABS = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_VERT_ABS", "EKF_POS_VERT_ABS") -f.EKF_STATUS_REPORT_flags_flagEKF_POS_VERT_AGL = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_VERT_AGL", "EKF_POS_VERT_AGL") -f.EKF_STATUS_REPORT_flags_flagEKF_CONST_POS_MODE = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_CONST_POS_MODE", "EKF_CONST_POS_MODE") -f.EKF_STATUS_REPORT_flags_flagEKF_PRED_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_PRED_POS_HORIZ_REL", "EKF_PRED_POS_HORIZ_REL") -f.EKF_STATUS_REPORT_flags_flagEKF_PRED_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_PRED_POS_HORIZ_ABS", "EKF_PRED_POS_HORIZ_ABS") -f.EKF_STATUS_REPORT_flags_flagEKF_UNINITIALIZED = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_UNINITIALIZED", "EKF_UNINITIALIZED") +f.EKF_STATUS_REPORT_flags_flagEKF_ATTITUDE = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_ATTITUDE", "EKF_ATTITUDE", 11, nil, 1) +f.EKF_STATUS_REPORT_flags_flagEKF_VELOCITY_HORIZ = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_VELOCITY_HORIZ", "EKF_VELOCITY_HORIZ", 11, nil, 2) +f.EKF_STATUS_REPORT_flags_flagEKF_VELOCITY_VERT = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_VELOCITY_VERT", "EKF_VELOCITY_VERT", 11, nil, 4) +f.EKF_STATUS_REPORT_flags_flagEKF_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_HORIZ_REL", "EKF_POS_HORIZ_REL", 11, nil, 8) +f.EKF_STATUS_REPORT_flags_flagEKF_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_HORIZ_ABS", "EKF_POS_HORIZ_ABS", 11, nil, 16) +f.EKF_STATUS_REPORT_flags_flagEKF_POS_VERT_ABS = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_VERT_ABS", "EKF_POS_VERT_ABS", 11, nil, 32) +f.EKF_STATUS_REPORT_flags_flagEKF_POS_VERT_AGL = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_POS_VERT_AGL", "EKF_POS_VERT_AGL", 11, nil, 64) +f.EKF_STATUS_REPORT_flags_flagEKF_CONST_POS_MODE = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_CONST_POS_MODE", "EKF_CONST_POS_MODE", 11, nil, 128) +f.EKF_STATUS_REPORT_flags_flagEKF_PRED_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_PRED_POS_HORIZ_REL", "EKF_PRED_POS_HORIZ_REL", 11, nil, 256) +f.EKF_STATUS_REPORT_flags_flagEKF_PRED_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_PRED_POS_HORIZ_ABS", "EKF_PRED_POS_HORIZ_ABS", 11, nil, 512) +f.EKF_STATUS_REPORT_flags_flagEKF_UNINITIALIZED = ProtoField.bool("mavlink_proto.EKF_STATUS_REPORT_flags.EKF_UNINITIALIZED", "EKF_UNINITIALIZED", 11, nil, 1024) f.EKF_STATUS_REPORT_velocity_variance = ProtoField.new("velocity_variance (float)", "mavlink_proto.EKF_STATUS_REPORT_velocity_variance", ftypes.FLOAT, nil) f.EKF_STATUS_REPORT_pos_horiz_variance = ProtoField.new("pos_horiz_variance (float)", "mavlink_proto.EKF_STATUS_REPORT_pos_horiz_variance", ftypes.FLOAT, nil) f.EKF_STATUS_REPORT_pos_vert_variance = ProtoField.new("pos_vert_variance (float)", "mavlink_proto.EKF_STATUS_REPORT_pos_vert_variance", ftypes.FLOAT, nil) @@ -3755,8 +3800,8 @@ f.GIMBAL_TORQUE_CMD_REPORT_az_torque_cmd = ProtoField.new("az_torque_cmd (int16_ f.GOPRO_HEARTBEAT_status = ProtoField.new("status (GOPRO_HEARTBEAT_STATUS)", "mavlink_proto.GOPRO_HEARTBEAT_status", ftypes.UINT8, enumEntryName.GOPRO_HEARTBEAT_STATUS) f.GOPRO_HEARTBEAT_capture_mode = ProtoField.new("capture_mode (GOPRO_CAPTURE_MODE)", "mavlink_proto.GOPRO_HEARTBEAT_capture_mode", ftypes.UINT8, enumEntryName.GOPRO_CAPTURE_MODE) f.GOPRO_HEARTBEAT_flags = ProtoField.new("flags (GOPRO_HEARTBEAT_FLAGS)", "mavlink_proto.GOPRO_HEARTBEAT_flags", ftypes.UINT8, nil) -f.GOPRO_HEARTBEAT_flags_flagGOPRO_FLAG_RECORDING = ProtoField.bool("mavlink_proto.GOPRO_HEARTBEAT_flags.GOPRO_FLAG_RECORDING", "GOPRO_FLAG_RECORDING") -f.GOPRO_HEARTBEAT_flags_flagGOPRO_HEARTBEAT_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.GOPRO_HEARTBEAT_flags.GOPRO_HEARTBEAT_FLAGS_ENUM_END", "GOPRO_HEARTBEAT_FLAGS_ENUM_END") +f.GOPRO_HEARTBEAT_flags_flagGOPRO_FLAG_RECORDING = ProtoField.bool("mavlink_proto.GOPRO_HEARTBEAT_flags.GOPRO_FLAG_RECORDING", "GOPRO_FLAG_RECORDING", 2, nil, 1) +f.GOPRO_HEARTBEAT_flags_flagGOPRO_HEARTBEAT_FLAGS_ENUM_END = ProtoField.bool("mavlink_proto.GOPRO_HEARTBEAT_flags.GOPRO_HEARTBEAT_FLAGS_ENUM_END", "GOPRO_HEARTBEAT_FLAGS_ENUM_END", 2, nil, 2) f.GOPRO_GET_REQUEST_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GOPRO_GET_REQUEST_target_system", ftypes.UINT8, nil) f.GOPRO_GET_REQUEST_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GOPRO_GET_REQUEST_target_component", ftypes.UINT8, nil) @@ -4816,101 +4861,101 @@ f.VIDEO_STREAM_INFORMATION99_rotation = ProtoField.new("rotation (uint16_t)", "m f.VIDEO_STREAM_INFORMATION99_uri = ProtoField.new("uri (char)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_uri", ftypes.STRING, nil) f.SYS_STATUS_onboard_control_sensors_present = ProtoField.new("onboard_control_sensors_present (MAV_SYS_STATUS_SENSOR)", "mavlink_proto.SYS_STATUS_onboard_control_sensors_present", ftypes.UINT32, nil) -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_ACCEL", "MAV_SYS_STATUS_SENSOR_3D_ACCEL") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_MAG = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_MAG", "MAV_SYS_STATUS_SENSOR_3D_MAG") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", "MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", "MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_GPS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_GPS", "MAV_SYS_STATUS_SENSOR_GPS") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", "MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_VISION_POSITION", "MAV_SYS_STATUS_SENSOR_VISION_POSITION") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_LASER_POSITION", "MAV_SYS_STATUS_SENSOR_LASER_POSITION") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", "MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", "MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", "MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_YAW_POSITION", "MAV_SYS_STATUS_SENSOR_YAW_POSITION") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", "MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", "MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", "MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_RC_RECEIVER", "MAV_SYS_STATUS_SENSOR_RC_RECEIVER") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_GYRO2", "MAV_SYS_STATUS_SENSOR_3D_GYRO2") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_ACCEL2", "MAV_SYS_STATUS_SENSOR_3D_ACCEL2") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_MAG2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_MAG2", "MAV_SYS_STATUS_SENSOR_3D_MAG2") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_GEOFENCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_GEOFENCE", "MAV_SYS_STATUS_GEOFENCE") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_AHRS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_AHRS", "MAV_SYS_STATUS_AHRS") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_TERRAIN = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_TERRAIN", "MAV_SYS_STATUS_TERRAIN") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_REVERSE_MOTOR = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_REVERSE_MOTOR", "MAV_SYS_STATUS_REVERSE_MOTOR") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_LOGGING = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_LOGGING", "MAV_SYS_STATUS_LOGGING") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_BATTERY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_BATTERY", "MAV_SYS_STATUS_SENSOR_BATTERY") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_PROXIMITY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_PROXIMITY", "MAV_SYS_STATUS_SENSOR_PROXIMITY") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_SATCOM = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_SATCOM", "MAV_SYS_STATUS_SENSOR_SATCOM") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_PREARM_CHECK = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_PREARM_CHECK", "MAV_SYS_STATUS_PREARM_CHECK") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", "MAV_SYS_STATUS_OBSTACLE_AVOIDANCE") -f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_PROPULSION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_PROPULSION", "MAV_SYS_STATUS_SENSOR_PROPULSION") +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO", 31, nil, 1) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_ACCEL", "MAV_SYS_STATUS_SENSOR_3D_ACCEL", 31, nil, 2) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_MAG = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_MAG", "MAV_SYS_STATUS_SENSOR_3D_MAG", 31, nil, 4) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", "MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", 31, nil, 8) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", "MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", 31, nil, 16) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_GPS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_GPS", "MAV_SYS_STATUS_SENSOR_GPS", 31, nil, 32) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", "MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", 31, nil, 64) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_VISION_POSITION", "MAV_SYS_STATUS_SENSOR_VISION_POSITION", 31, nil, 128) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_LASER_POSITION", "MAV_SYS_STATUS_SENSOR_LASER_POSITION", 31, nil, 256) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", "MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", 31, nil, 512) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", "MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", 31, nil, 1024) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", "MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", 31, nil, 2048) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_YAW_POSITION", "MAV_SYS_STATUS_SENSOR_YAW_POSITION", 31, nil, 4096) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", "MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", 31, nil, 8192) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", "MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", 31, nil, 16384) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", "MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", 31, nil, 32768) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_RC_RECEIVER", "MAV_SYS_STATUS_SENSOR_RC_RECEIVER", 31, nil, 65536) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_GYRO2", "MAV_SYS_STATUS_SENSOR_3D_GYRO2", 31, nil, 131072) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_ACCEL2", "MAV_SYS_STATUS_SENSOR_3D_ACCEL2", 31, nil, 262144) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_3D_MAG2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_3D_MAG2", "MAV_SYS_STATUS_SENSOR_3D_MAG2", 31, nil, 524288) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_GEOFENCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_GEOFENCE", "MAV_SYS_STATUS_GEOFENCE", 31, nil, 1048576) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_AHRS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_AHRS", "MAV_SYS_STATUS_AHRS", 31, nil, 2097152) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_TERRAIN = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_TERRAIN", "MAV_SYS_STATUS_TERRAIN", 31, nil, 4194304) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_REVERSE_MOTOR = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_REVERSE_MOTOR", "MAV_SYS_STATUS_REVERSE_MOTOR", 31, nil, 8388608) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_LOGGING = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_LOGGING", "MAV_SYS_STATUS_LOGGING", 31, nil, 16777216) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_BATTERY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_BATTERY", "MAV_SYS_STATUS_SENSOR_BATTERY", 31, nil, 33554432) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_PROXIMITY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_PROXIMITY", "MAV_SYS_STATUS_SENSOR_PROXIMITY", 31, nil, 67108864) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_SATCOM = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_SATCOM", "MAV_SYS_STATUS_SENSOR_SATCOM", 31, nil, 134217728) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_PREARM_CHECK = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_PREARM_CHECK", "MAV_SYS_STATUS_PREARM_CHECK", 31, nil, 268435456) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", "MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", 31, nil, 536870912) +f.SYS_STATUS_onboard_control_sensors_present_flagMAV_SYS_STATUS_SENSOR_PROPULSION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_present.MAV_SYS_STATUS_SENSOR_PROPULSION", "MAV_SYS_STATUS_SENSOR_PROPULSION", 31, nil, 1073741824) f.SYS_STATUS_onboard_control_sensors_enabled = ProtoField.new("onboard_control_sensors_enabled (MAV_SYS_STATUS_SENSOR)", "mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled", ftypes.UINT32, nil) -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_ACCEL", "MAV_SYS_STATUS_SENSOR_3D_ACCEL") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_MAG = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_MAG", "MAV_SYS_STATUS_SENSOR_3D_MAG") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", "MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", "MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_GPS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_GPS", "MAV_SYS_STATUS_SENSOR_GPS") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", "MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_VISION_POSITION", "MAV_SYS_STATUS_SENSOR_VISION_POSITION") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_LASER_POSITION", "MAV_SYS_STATUS_SENSOR_LASER_POSITION") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", "MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", "MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", "MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_YAW_POSITION", "MAV_SYS_STATUS_SENSOR_YAW_POSITION") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", "MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", "MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", "MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_RC_RECEIVER", "MAV_SYS_STATUS_SENSOR_RC_RECEIVER") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_GYRO2", "MAV_SYS_STATUS_SENSOR_3D_GYRO2") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_ACCEL2", "MAV_SYS_STATUS_SENSOR_3D_ACCEL2") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_MAG2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_MAG2", "MAV_SYS_STATUS_SENSOR_3D_MAG2") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_GEOFENCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_GEOFENCE", "MAV_SYS_STATUS_GEOFENCE") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_AHRS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_AHRS", "MAV_SYS_STATUS_AHRS") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_TERRAIN = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_TERRAIN", "MAV_SYS_STATUS_TERRAIN") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_REVERSE_MOTOR = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_REVERSE_MOTOR", "MAV_SYS_STATUS_REVERSE_MOTOR") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_LOGGING = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_LOGGING", "MAV_SYS_STATUS_LOGGING") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_BATTERY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_BATTERY", "MAV_SYS_STATUS_SENSOR_BATTERY") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_PROXIMITY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_PROXIMITY", "MAV_SYS_STATUS_SENSOR_PROXIMITY") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_SATCOM = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_SATCOM", "MAV_SYS_STATUS_SENSOR_SATCOM") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_PREARM_CHECK = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_PREARM_CHECK", "MAV_SYS_STATUS_PREARM_CHECK") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", "MAV_SYS_STATUS_OBSTACLE_AVOIDANCE") -f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_PROPULSION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_PROPULSION", "MAV_SYS_STATUS_SENSOR_PROPULSION") +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO", 31, nil, 1) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_ACCEL", "MAV_SYS_STATUS_SENSOR_3D_ACCEL", 31, nil, 2) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_MAG = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_MAG", "MAV_SYS_STATUS_SENSOR_3D_MAG", 31, nil, 4) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", "MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", 31, nil, 8) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", "MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", 31, nil, 16) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_GPS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_GPS", "MAV_SYS_STATUS_SENSOR_GPS", 31, nil, 32) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", "MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", 31, nil, 64) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_VISION_POSITION", "MAV_SYS_STATUS_SENSOR_VISION_POSITION", 31, nil, 128) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_LASER_POSITION", "MAV_SYS_STATUS_SENSOR_LASER_POSITION", 31, nil, 256) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", "MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", 31, nil, 512) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", "MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", 31, nil, 1024) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", "MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", 31, nil, 2048) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_YAW_POSITION", "MAV_SYS_STATUS_SENSOR_YAW_POSITION", 31, nil, 4096) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", "MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", 31, nil, 8192) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", "MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", 31, nil, 16384) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", "MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", 31, nil, 32768) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_RC_RECEIVER", "MAV_SYS_STATUS_SENSOR_RC_RECEIVER", 31, nil, 65536) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_GYRO2", "MAV_SYS_STATUS_SENSOR_3D_GYRO2", 31, nil, 131072) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_ACCEL2", "MAV_SYS_STATUS_SENSOR_3D_ACCEL2", 31, nil, 262144) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_3D_MAG2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_3D_MAG2", "MAV_SYS_STATUS_SENSOR_3D_MAG2", 31, nil, 524288) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_GEOFENCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_GEOFENCE", "MAV_SYS_STATUS_GEOFENCE", 31, nil, 1048576) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_AHRS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_AHRS", "MAV_SYS_STATUS_AHRS", 31, nil, 2097152) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_TERRAIN = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_TERRAIN", "MAV_SYS_STATUS_TERRAIN", 31, nil, 4194304) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_REVERSE_MOTOR = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_REVERSE_MOTOR", "MAV_SYS_STATUS_REVERSE_MOTOR", 31, nil, 8388608) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_LOGGING = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_LOGGING", "MAV_SYS_STATUS_LOGGING", 31, nil, 16777216) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_BATTERY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_BATTERY", "MAV_SYS_STATUS_SENSOR_BATTERY", 31, nil, 33554432) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_PROXIMITY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_PROXIMITY", "MAV_SYS_STATUS_SENSOR_PROXIMITY", 31, nil, 67108864) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_SATCOM = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_SATCOM", "MAV_SYS_STATUS_SENSOR_SATCOM", 31, nil, 134217728) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_PREARM_CHECK = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_PREARM_CHECK", "MAV_SYS_STATUS_PREARM_CHECK", 31, nil, 268435456) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", "MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", 31, nil, 536870912) +f.SYS_STATUS_onboard_control_sensors_enabled_flagMAV_SYS_STATUS_SENSOR_PROPULSION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_enabled.MAV_SYS_STATUS_SENSOR_PROPULSION", "MAV_SYS_STATUS_SENSOR_PROPULSION", 31, nil, 1073741824) f.SYS_STATUS_onboard_control_sensors_health = ProtoField.new("onboard_control_sensors_health (MAV_SYS_STATUS_SENSOR)", "mavlink_proto.SYS_STATUS_onboard_control_sensors_health", ftypes.UINT32, nil) -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_ACCEL", "MAV_SYS_STATUS_SENSOR_3D_ACCEL") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_MAG = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_MAG", "MAV_SYS_STATUS_SENSOR_3D_MAG") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", "MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", "MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_GPS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_GPS", "MAV_SYS_STATUS_SENSOR_GPS") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", "MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_VISION_POSITION", "MAV_SYS_STATUS_SENSOR_VISION_POSITION") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_LASER_POSITION", "MAV_SYS_STATUS_SENSOR_LASER_POSITION") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", "MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", "MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", "MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_YAW_POSITION", "MAV_SYS_STATUS_SENSOR_YAW_POSITION") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", "MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", "MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", "MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_RC_RECEIVER", "MAV_SYS_STATUS_SENSOR_RC_RECEIVER") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_GYRO2", "MAV_SYS_STATUS_SENSOR_3D_GYRO2") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_ACCEL2", "MAV_SYS_STATUS_SENSOR_3D_ACCEL2") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_MAG2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_MAG2", "MAV_SYS_STATUS_SENSOR_3D_MAG2") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_GEOFENCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_GEOFENCE", "MAV_SYS_STATUS_GEOFENCE") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_AHRS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_AHRS", "MAV_SYS_STATUS_AHRS") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_TERRAIN = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_TERRAIN", "MAV_SYS_STATUS_TERRAIN") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_REVERSE_MOTOR = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_REVERSE_MOTOR", "MAV_SYS_STATUS_REVERSE_MOTOR") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_LOGGING = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_LOGGING", "MAV_SYS_STATUS_LOGGING") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_BATTERY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_BATTERY", "MAV_SYS_STATUS_SENSOR_BATTERY") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_PROXIMITY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_PROXIMITY", "MAV_SYS_STATUS_SENSOR_PROXIMITY") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_SATCOM = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_SATCOM", "MAV_SYS_STATUS_SENSOR_SATCOM") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_PREARM_CHECK = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_PREARM_CHECK", "MAV_SYS_STATUS_PREARM_CHECK") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", "MAV_SYS_STATUS_OBSTACLE_AVOIDANCE") -f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_PROPULSION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_PROPULSION", "MAV_SYS_STATUS_SENSOR_PROPULSION") +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_GYRO = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_GYRO", "MAV_SYS_STATUS_SENSOR_3D_GYRO", 31, nil, 1) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_ACCEL", "MAV_SYS_STATUS_SENSOR_3D_ACCEL", 31, nil, 2) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_MAG = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_MAG", "MAV_SYS_STATUS_SENSOR_3D_MAG", 31, nil, 4) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", "MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE", 31, nil, 8) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", "MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE", 31, nil, 16) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_GPS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_GPS", "MAV_SYS_STATUS_SENSOR_GPS", 31, nil, 32) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", "MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW", 31, nil, 64) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_VISION_POSITION", "MAV_SYS_STATUS_SENSOR_VISION_POSITION", 31, nil, 128) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_LASER_POSITION", "MAV_SYS_STATUS_SENSOR_LASER_POSITION", 31, nil, 256) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", "MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH", 31, nil, 512) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", "MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL", 31, nil, 1024) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", "MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION", 31, nil, 2048) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_YAW_POSITION", "MAV_SYS_STATUS_SENSOR_YAW_POSITION", 31, nil, 4096) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", "MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL", 31, nil, 8192) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", "MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL", 31, nil, 16384) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", "MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS", 31, nil, 32768) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_RC_RECEIVER", "MAV_SYS_STATUS_SENSOR_RC_RECEIVER", 31, nil, 65536) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_GYRO2", "MAV_SYS_STATUS_SENSOR_3D_GYRO2", 31, nil, 131072) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_ACCEL2", "MAV_SYS_STATUS_SENSOR_3D_ACCEL2", 31, nil, 262144) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_3D_MAG2 = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_3D_MAG2", "MAV_SYS_STATUS_SENSOR_3D_MAG2", 31, nil, 524288) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_GEOFENCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_GEOFENCE", "MAV_SYS_STATUS_GEOFENCE", 31, nil, 1048576) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_AHRS = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_AHRS", "MAV_SYS_STATUS_AHRS", 31, nil, 2097152) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_TERRAIN = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_TERRAIN", "MAV_SYS_STATUS_TERRAIN", 31, nil, 4194304) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_REVERSE_MOTOR = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_REVERSE_MOTOR", "MAV_SYS_STATUS_REVERSE_MOTOR", 31, nil, 8388608) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_LOGGING = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_LOGGING", "MAV_SYS_STATUS_LOGGING", 31, nil, 16777216) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_BATTERY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_BATTERY", "MAV_SYS_STATUS_SENSOR_BATTERY", 31, nil, 33554432) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_PROXIMITY = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_PROXIMITY", "MAV_SYS_STATUS_SENSOR_PROXIMITY", 31, nil, 67108864) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_SATCOM = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_SATCOM", "MAV_SYS_STATUS_SENSOR_SATCOM", 31, nil, 134217728) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_PREARM_CHECK = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_PREARM_CHECK", "MAV_SYS_STATUS_PREARM_CHECK", 31, nil, 268435456) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", "MAV_SYS_STATUS_OBSTACLE_AVOIDANCE", 31, nil, 536870912) +f.SYS_STATUS_onboard_control_sensors_health_flagMAV_SYS_STATUS_SENSOR_PROPULSION = ProtoField.bool("mavlink_proto.SYS_STATUS_onboard_control_sensors_health.MAV_SYS_STATUS_SENSOR_PROPULSION", "MAV_SYS_STATUS_SENSOR_PROPULSION", 31, nil, 1073741824) f.SYS_STATUS_load = ProtoField.new("load (uint16_t)", "mavlink_proto.SYS_STATUS_load", ftypes.UINT16, nil) f.SYS_STATUS_voltage_battery = ProtoField.new("voltage_battery (uint16_t)", "mavlink_proto.SYS_STATUS_voltage_battery", ftypes.UINT16, nil) f.SYS_STATUS_current_battery = ProtoField.new("current_battery (int16_t)", "mavlink_proto.SYS_STATUS_current_battery", ftypes.INT16, nil) @@ -5241,6 +5286,9 @@ f.MISSION_SET_CURRENT_target_component = ProtoField.new("target_component (uint8 f.MISSION_SET_CURRENT_seq = ProtoField.new("seq (uint16_t)", "mavlink_proto.MISSION_SET_CURRENT_seq", ftypes.UINT16, nil) f.MISSION_CURRENT_seq = ProtoField.new("seq (uint16_t)", "mavlink_proto.MISSION_CURRENT_seq", ftypes.UINT16, nil) +f.MISSION_CURRENT_total = ProtoField.new("total (uint16_t)", "mavlink_proto.MISSION_CURRENT_total", ftypes.UINT16, nil) +f.MISSION_CURRENT_mission_state = ProtoField.new("mission_state (MISSION_STATE)", "mavlink_proto.MISSION_CURRENT_mission_state", ftypes.UINT8, enumEntryName.MISSION_STATE) +f.MISSION_CURRENT_mission_mode = ProtoField.new("mission_mode (uint8_t)", "mavlink_proto.MISSION_CURRENT_mission_mode", ftypes.UINT8, nil) f.MISSION_REQUEST_LIST_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.MISSION_REQUEST_LIST_target_system", ftypes.UINT8, nil) f.MISSION_REQUEST_LIST_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.MISSION_REQUEST_LIST_target_component", ftypes.UINT8, nil) @@ -5564,11 +5612,11 @@ f.SET_ATTITUDE_TARGET_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", " f.SET_ATTITUDE_TARGET_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.SET_ATTITUDE_TARGET_target_system", ftypes.UINT8, nil) f.SET_ATTITUDE_TARGET_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.SET_ATTITUDE_TARGET_target_component", ftypes.UINT8, nil) f.SET_ATTITUDE_TARGET_type_mask = ProtoField.new("type_mask (ATTITUDE_TARGET_TYPEMASK)", "mavlink_proto.SET_ATTITUDE_TARGET_type_mask", ftypes.UINT8, nil) -f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE") -f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE") -f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE") -f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE") -f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE") +f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE", 8, nil, 1) +f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE", 8, nil, 2) +f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE", 8, nil, 4) +f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE", 8, nil, 64) +f.SET_ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = ProtoField.bool("mavlink_proto.SET_ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE", 8, nil, 128) f.SET_ATTITUDE_TARGET_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.SET_ATTITUDE_TARGET_q_0", ftypes.FLOAT, nil) f.SET_ATTITUDE_TARGET_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.SET_ATTITUDE_TARGET_q_1", ftypes.FLOAT, nil) f.SET_ATTITUDE_TARGET_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.SET_ATTITUDE_TARGET_q_2", ftypes.FLOAT, nil) @@ -5580,11 +5628,11 @@ f.SET_ATTITUDE_TARGET_thrust = ProtoField.new("thrust (float)", "mavlink_proto.S f.ATTITUDE_TARGET_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.ATTITUDE_TARGET_time_boot_ms", ftypes.UINT32, nil) f.ATTITUDE_TARGET_type_mask = ProtoField.new("type_mask (ATTITUDE_TARGET_TYPEMASK)", "mavlink_proto.ATTITUDE_TARGET_type_mask", ftypes.UINT8, nil) -f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE") -f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE") -f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE") -f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE") -f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE") +f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE", 8, nil, 1) +f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE", 8, nil, 2) +f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE", 8, nil, 4) +f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE", 8, nil, 64) +f.ATTITUDE_TARGET_type_mask_flagATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = ProtoField.bool("mavlink_proto.ATTITUDE_TARGET_type_mask.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE", "ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE", 8, nil, 128) f.ATTITUDE_TARGET_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.ATTITUDE_TARGET_q_0", ftypes.FLOAT, nil) f.ATTITUDE_TARGET_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.ATTITUDE_TARGET_q_1", ftypes.FLOAT, nil) f.ATTITUDE_TARGET_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.ATTITUDE_TARGET_q_2", ftypes.FLOAT, nil) @@ -5599,18 +5647,18 @@ f.SET_POSITION_TARGET_LOCAL_NED_target_system = ProtoField.new("target_system (u f.SET_POSITION_TARGET_LOCAL_NED_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_target_component", ftypes.UINT8, nil) f.SET_POSITION_TARGET_LOCAL_NED_coordinate_frame = ProtoField.new("coordinate_frame (MAV_FRAME)", "mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_coordinate_frame", ftypes.UINT8, enumEntryName.MAV_FRAME) f.SET_POSITION_TARGET_LOCAL_NED_type_mask = ProtoField.new("type_mask (POSITION_TARGET_TYPEMASK)", "mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask", ftypes.UINT16, nil) -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE") -f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE") +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE", 12, nil, 1) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE", 12, nil, 2) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE", 12, nil, 4) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE", 12, nil, 8) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE", 12, nil, 16) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE", 12, nil, 32) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE", 12, nil, 64) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE", 12, nil, 128) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE", 12, nil, 256) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET", 12, nil, 512) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE", 12, nil, 1024) +f.SET_POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", 12, nil, 2048) f.SET_POSITION_TARGET_LOCAL_NED_x = ProtoField.new("x (float)", "mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_x", ftypes.FLOAT, nil) f.SET_POSITION_TARGET_LOCAL_NED_y = ProtoField.new("y (float)", "mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_y", ftypes.FLOAT, nil) f.SET_POSITION_TARGET_LOCAL_NED_z = ProtoField.new("z (float)", "mavlink_proto.SET_POSITION_TARGET_LOCAL_NED_z", ftypes.FLOAT, nil) @@ -5626,18 +5674,18 @@ f.SET_POSITION_TARGET_LOCAL_NED_yaw_rate = ProtoField.new("yaw_rate (float)", "m f.POSITION_TARGET_LOCAL_NED_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.POSITION_TARGET_LOCAL_NED_time_boot_ms", ftypes.UINT32, nil) f.POSITION_TARGET_LOCAL_NED_coordinate_frame = ProtoField.new("coordinate_frame (MAV_FRAME)", "mavlink_proto.POSITION_TARGET_LOCAL_NED_coordinate_frame", ftypes.UINT8, enumEntryName.MAV_FRAME) f.POSITION_TARGET_LOCAL_NED_type_mask = ProtoField.new("type_mask (POSITION_TARGET_TYPEMASK)", "mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask", ftypes.UINT16, nil) -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE") -f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE") +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE", 12, nil, 1) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE", 12, nil, 2) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE", 12, nil, 4) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE", 12, nil, 8) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE", 12, nil, 16) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE", 12, nil, 32) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE", 12, nil, 64) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE", 12, nil, 128) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE", 12, nil, 256) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET", 12, nil, 512) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE", 12, nil, 1024) +f.POSITION_TARGET_LOCAL_NED_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_LOCAL_NED_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", 12, nil, 2048) f.POSITION_TARGET_LOCAL_NED_x = ProtoField.new("x (float)", "mavlink_proto.POSITION_TARGET_LOCAL_NED_x", ftypes.FLOAT, nil) f.POSITION_TARGET_LOCAL_NED_y = ProtoField.new("y (float)", "mavlink_proto.POSITION_TARGET_LOCAL_NED_y", ftypes.FLOAT, nil) f.POSITION_TARGET_LOCAL_NED_z = ProtoField.new("z (float)", "mavlink_proto.POSITION_TARGET_LOCAL_NED_z", ftypes.FLOAT, nil) @@ -5655,18 +5703,18 @@ f.SET_POSITION_TARGET_GLOBAL_INT_target_system = ProtoField.new("target_system ( f.SET_POSITION_TARGET_GLOBAL_INT_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_target_component", ftypes.UINT8, nil) f.SET_POSITION_TARGET_GLOBAL_INT_coordinate_frame = ProtoField.new("coordinate_frame (MAV_FRAME)", "mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_coordinate_frame", ftypes.UINT8, enumEntryName.MAV_FRAME) f.SET_POSITION_TARGET_GLOBAL_INT_type_mask = ProtoField.new("type_mask (POSITION_TARGET_TYPEMASK)", "mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask", ftypes.UINT16, nil) -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE") -f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE") +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE", 12, nil, 1) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE", 12, nil, 2) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE", 12, nil, 4) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE", 12, nil, 8) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE", 12, nil, 16) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE", 12, nil, 32) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE", 12, nil, 64) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE", 12, nil, 128) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE", 12, nil, 256) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET", 12, nil, 512) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE", 12, nil, 1024) +f.SET_POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", 12, nil, 2048) f.SET_POSITION_TARGET_GLOBAL_INT_lat_int = ProtoField.new("lat_int (int32_t)", "mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_lat_int", ftypes.INT32, nil) f.SET_POSITION_TARGET_GLOBAL_INT_lon_int = ProtoField.new("lon_int (int32_t)", "mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_lon_int", ftypes.INT32, nil) f.SET_POSITION_TARGET_GLOBAL_INT_alt = ProtoField.new("alt (float)", "mavlink_proto.SET_POSITION_TARGET_GLOBAL_INT_alt", ftypes.FLOAT, nil) @@ -5682,18 +5730,18 @@ f.SET_POSITION_TARGET_GLOBAL_INT_yaw_rate = ProtoField.new("yaw_rate (float)", " f.POSITION_TARGET_GLOBAL_INT_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.POSITION_TARGET_GLOBAL_INT_time_boot_ms", ftypes.UINT32, nil) f.POSITION_TARGET_GLOBAL_INT_coordinate_frame = ProtoField.new("coordinate_frame (MAV_FRAME)", "mavlink_proto.POSITION_TARGET_GLOBAL_INT_coordinate_frame", ftypes.UINT8, enumEntryName.MAV_FRAME) f.POSITION_TARGET_GLOBAL_INT_type_mask = ProtoField.new("type_mask (POSITION_TARGET_TYPEMASK)", "mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask", ftypes.UINT16, nil) -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE") -f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE") +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_X_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_X_IGNORE", "POSITION_TARGET_TYPEMASK_X_IGNORE", 12, nil, 1) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Y_IGNORE", "POSITION_TARGET_TYPEMASK_Y_IGNORE", 12, nil, 2) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_Z_IGNORE", "POSITION_TARGET_TYPEMASK_Z_IGNORE", 12, nil, 4) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VX_IGNORE", "POSITION_TARGET_TYPEMASK_VX_IGNORE", 12, nil, 8) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VY_IGNORE", "POSITION_TARGET_TYPEMASK_VY_IGNORE", 12, nil, 16) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_VZ_IGNORE", "POSITION_TARGET_TYPEMASK_VZ_IGNORE", 12, nil, 32) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AX_IGNORE", "POSITION_TARGET_TYPEMASK_AX_IGNORE", 12, nil, 64) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AY_IGNORE", "POSITION_TARGET_TYPEMASK_AY_IGNORE", 12, nil, 128) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_AZ_IGNORE", "POSITION_TARGET_TYPEMASK_AZ_IGNORE", 12, nil, 256) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_FORCE_SET = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_FORCE_SET", "POSITION_TARGET_TYPEMASK_FORCE_SET", 12, nil, 512) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_IGNORE", 12, nil, 1024) +f.POSITION_TARGET_GLOBAL_INT_type_mask_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = ProtoField.bool("mavlink_proto.POSITION_TARGET_GLOBAL_INT_type_mask.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", "POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE", 12, nil, 2048) f.POSITION_TARGET_GLOBAL_INT_lat_int = ProtoField.new("lat_int (int32_t)", "mavlink_proto.POSITION_TARGET_GLOBAL_INT_lat_int", ftypes.INT32, nil) f.POSITION_TARGET_GLOBAL_INT_lon_int = ProtoField.new("lon_int (int32_t)", "mavlink_proto.POSITION_TARGET_GLOBAL_INT_lon_int", ftypes.INT32, nil) f.POSITION_TARGET_GLOBAL_INT_alt = ProtoField.new("alt (float)", "mavlink_proto.POSITION_TARGET_GLOBAL_INT_alt", ftypes.FLOAT, nil) @@ -5776,14 +5824,14 @@ f.HIL_ACTUATOR_CONTROLS_controls_13 = ProtoField.new("controls[13] (float)", "ma f.HIL_ACTUATOR_CONTROLS_controls_14 = ProtoField.new("controls[14] (float)", "mavlink_proto.HIL_ACTUATOR_CONTROLS_controls_14", ftypes.FLOAT, nil) f.HIL_ACTUATOR_CONTROLS_controls_15 = ProtoField.new("controls[15] (float)", "mavlink_proto.HIL_ACTUATOR_CONTROLS_controls_15", ftypes.FLOAT, nil) f.HIL_ACTUATOR_CONTROLS_mode = ProtoField.new("mode (MAV_MODE_FLAG)", "mavlink_proto.HIL_ACTUATOR_CONTROLS_mode", ftypes.UINT8, nil) -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED") -f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED") +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", 8, nil, 1) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED", 8, nil, 2) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED", 8, nil, 4) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED", 8, nil, 8) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED", 8, nil, 16) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED", 8, nil, 32) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", 8, nil, 64) +f.HIL_ACTUATOR_CONTROLS_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HIL_ACTUATOR_CONTROLS_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED", 8, nil, 128) f.HIL_ACTUATOR_CONTROLS_flags = ProtoField.new("flags (uint64_t)", "mavlink_proto.HIL_ACTUATOR_CONTROLS_flags", ftypes.UINT64, nil) f.OPTICAL_FLOW_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.OPTICAL_FLOW_time_usec", ftypes.UINT64, nil) @@ -6553,20 +6601,20 @@ f.GPS2_RAW_hdg_acc = ProtoField.new("hdg_acc (uint32_t)", "mavlink_proto.GPS2_RA f.POWER_STATUS_Vcc = ProtoField.new("Vcc (uint16_t)", "mavlink_proto.POWER_STATUS_Vcc", ftypes.UINT16, nil) f.POWER_STATUS_Vservo = ProtoField.new("Vservo (uint16_t)", "mavlink_proto.POWER_STATUS_Vservo", ftypes.UINT16, nil) f.POWER_STATUS_flags = ProtoField.new("flags (MAV_POWER_STATUS)", "mavlink_proto.POWER_STATUS_flags", ftypes.UINT16, nil) -f.POWER_STATUS_flags_flagMAV_POWER_STATUS_BRICK_VALID = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_BRICK_VALID", "MAV_POWER_STATUS_BRICK_VALID") -f.POWER_STATUS_flags_flagMAV_POWER_STATUS_SERVO_VALID = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_SERVO_VALID", "MAV_POWER_STATUS_SERVO_VALID") -f.POWER_STATUS_flags_flagMAV_POWER_STATUS_USB_CONNECTED = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_USB_CONNECTED", "MAV_POWER_STATUS_USB_CONNECTED") -f.POWER_STATUS_flags_flagMAV_POWER_STATUS_PERIPH_OVERCURRENT = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_PERIPH_OVERCURRENT", "MAV_POWER_STATUS_PERIPH_OVERCURRENT") -f.POWER_STATUS_flags_flagMAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT", "MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT") -f.POWER_STATUS_flags_flagMAV_POWER_STATUS_CHANGED = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_CHANGED", "MAV_POWER_STATUS_CHANGED") +f.POWER_STATUS_flags_flagMAV_POWER_STATUS_BRICK_VALID = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_BRICK_VALID", "MAV_POWER_STATUS_BRICK_VALID", 6, nil, 1) +f.POWER_STATUS_flags_flagMAV_POWER_STATUS_SERVO_VALID = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_SERVO_VALID", "MAV_POWER_STATUS_SERVO_VALID", 6, nil, 2) +f.POWER_STATUS_flags_flagMAV_POWER_STATUS_USB_CONNECTED = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_USB_CONNECTED", "MAV_POWER_STATUS_USB_CONNECTED", 6, nil, 4) +f.POWER_STATUS_flags_flagMAV_POWER_STATUS_PERIPH_OVERCURRENT = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_PERIPH_OVERCURRENT", "MAV_POWER_STATUS_PERIPH_OVERCURRENT", 6, nil, 8) +f.POWER_STATUS_flags_flagMAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT", "MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT", 6, nil, 16) +f.POWER_STATUS_flags_flagMAV_POWER_STATUS_CHANGED = ProtoField.bool("mavlink_proto.POWER_STATUS_flags.MAV_POWER_STATUS_CHANGED", "MAV_POWER_STATUS_CHANGED", 6, nil, 32) f.SERIAL_CONTROL_device = ProtoField.new("device (SERIAL_CONTROL_DEV)", "mavlink_proto.SERIAL_CONTROL_device", ftypes.UINT8, enumEntryName.SERIAL_CONTROL_DEV) f.SERIAL_CONTROL_flags = ProtoField.new("flags (SERIAL_CONTROL_FLAG)", "mavlink_proto.SERIAL_CONTROL_flags", ftypes.UINT8, nil) -f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_REPLY = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_REPLY", "SERIAL_CONTROL_FLAG_REPLY") -f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_RESPOND = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_RESPOND", "SERIAL_CONTROL_FLAG_RESPOND") -f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_EXCLUSIVE = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_EXCLUSIVE", "SERIAL_CONTROL_FLAG_EXCLUSIVE") -f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_BLOCKING = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_BLOCKING", "SERIAL_CONTROL_FLAG_BLOCKING") -f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_MULTI = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_MULTI", "SERIAL_CONTROL_FLAG_MULTI") +f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_REPLY = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_REPLY", "SERIAL_CONTROL_FLAG_REPLY", 5, nil, 1) +f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_RESPOND = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_RESPOND", "SERIAL_CONTROL_FLAG_RESPOND", 5, nil, 2) +f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_EXCLUSIVE = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_EXCLUSIVE", "SERIAL_CONTROL_FLAG_EXCLUSIVE", 5, nil, 4) +f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_BLOCKING = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_BLOCKING", "SERIAL_CONTROL_FLAG_BLOCKING", 5, nil, 8) +f.SERIAL_CONTROL_flags_flagSERIAL_CONTROL_FLAG_MULTI = ProtoField.bool("mavlink_proto.SERIAL_CONTROL_flags.SERIAL_CONTROL_FLAG_MULTI", "SERIAL_CONTROL_FLAG_MULTI", 5, nil, 16) f.SERIAL_CONTROL_timeout = ProtoField.new("timeout (uint16_t)", "mavlink_proto.SERIAL_CONTROL_timeout", ftypes.UINT16, nil) f.SERIAL_CONTROL_baudrate = ProtoField.new("baudrate (uint32_t)", "mavlink_proto.SERIAL_CONTROL_baudrate", ftypes.UINT32, nil) f.SERIAL_CONTROL_count = ProtoField.new("count (uint8_t)", "mavlink_proto.SERIAL_CONTROL_count", ftypes.UINT8, nil) @@ -7389,34 +7437,34 @@ f.BATTERY_STATUS_voltages_ext_2 = ProtoField.new("voltages_ext[2] (uint16_t)", " f.BATTERY_STATUS_voltages_ext_3 = ProtoField.new("voltages_ext[3] (uint16_t)", "mavlink_proto.BATTERY_STATUS_voltages_ext_3", ftypes.UINT16, nil) f.BATTERY_STATUS_mode = ProtoField.new("mode (MAV_BATTERY_MODE)", "mavlink_proto.BATTERY_STATUS_mode", ftypes.UINT8, enumEntryName.MAV_BATTERY_MODE) f.BATTERY_STATUS_fault_bitmask = ProtoField.new("fault_bitmask (MAV_BATTERY_FAULT)", "mavlink_proto.BATTERY_STATUS_fault_bitmask", ftypes.UINT32, nil) -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_DEEP_DISCHARGE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_DEEP_DISCHARGE", "MAV_BATTERY_FAULT_DEEP_DISCHARGE") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_SPIKES = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_SPIKES", "MAV_BATTERY_FAULT_SPIKES") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_CELL_FAIL = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_CELL_FAIL", "MAV_BATTERY_FAULT_CELL_FAIL") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_OVER_CURRENT = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_OVER_CURRENT", "MAV_BATTERY_FAULT_OVER_CURRENT") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_OVER_TEMPERATURE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_OVER_TEMPERATURE", "MAV_BATTERY_FAULT_OVER_TEMPERATURE") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_UNDER_TEMPERATURE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_UNDER_TEMPERATURE", "MAV_BATTERY_FAULT_UNDER_TEMPERATURE") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE", "MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE") -f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE", "MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE") -f.BATTERY_STATUS_fault_bitmask_flagBATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION", "BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION") +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_DEEP_DISCHARGE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_DEEP_DISCHARGE", "MAV_BATTERY_FAULT_DEEP_DISCHARGE", 9, nil, 1) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_SPIKES = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_SPIKES", "MAV_BATTERY_FAULT_SPIKES", 9, nil, 2) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_CELL_FAIL = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_CELL_FAIL", "MAV_BATTERY_FAULT_CELL_FAIL", 9, nil, 4) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_OVER_CURRENT = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_OVER_CURRENT", "MAV_BATTERY_FAULT_OVER_CURRENT", 9, nil, 8) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_OVER_TEMPERATURE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_OVER_TEMPERATURE", "MAV_BATTERY_FAULT_OVER_TEMPERATURE", 9, nil, 16) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_UNDER_TEMPERATURE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_UNDER_TEMPERATURE", "MAV_BATTERY_FAULT_UNDER_TEMPERATURE", 9, nil, 32) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE", "MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE", 9, nil, 64) +f.BATTERY_STATUS_fault_bitmask_flagMAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE", "MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE", 9, nil, 128) +f.BATTERY_STATUS_fault_bitmask_flagBATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = ProtoField.bool("mavlink_proto.BATTERY_STATUS_fault_bitmask.BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION", "BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION", 9, nil, 256) f.AUTOPILOT_VERSION_capabilities = ProtoField.new("capabilities (MAV_PROTOCOL_CAPABILITY)", "mavlink_proto.AUTOPILOT_VERSION_capabilities", ftypes.UINT64, nil) -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT", "MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT", "MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_INT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_INT", "MAV_PROTOCOL_CAPABILITY_MISSION_INT") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_COMMAND_INT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_COMMAND_INT", "MAV_PROTOCOL_CAPABILITY_COMMAND_INT") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_PARAM_UNION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_PARAM_UNION", "MAV_PROTOCOL_CAPABILITY_PARAM_UNION") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_FTP = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_FTP", "MAV_PROTOCOL_CAPABILITY_FTP") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET", "MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED", "MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT", "MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_TERRAIN = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_TERRAIN", "MAV_PROTOCOL_CAPABILITY_TERRAIN") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET", "MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION", "MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION", "MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MAVLINK2 = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MAVLINK2", "MAV_PROTOCOL_CAPABILITY_MAVLINK2") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_FENCE = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_FENCE", "MAV_PROTOCOL_CAPABILITY_MISSION_FENCE") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_RALLY = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_RALLY", "MAV_PROTOCOL_CAPABILITY_MISSION_RALLY") -f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION", "MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION") +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT", "MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT", 17, nil, 1) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT", "MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT", 17, nil, 2) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_INT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_INT", "MAV_PROTOCOL_CAPABILITY_MISSION_INT", 17, nil, 4) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_COMMAND_INT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_COMMAND_INT", "MAV_PROTOCOL_CAPABILITY_COMMAND_INT", 17, nil, 8) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_PARAM_UNION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_PARAM_UNION", "MAV_PROTOCOL_CAPABILITY_PARAM_UNION", 17, nil, 16) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_FTP = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_FTP", "MAV_PROTOCOL_CAPABILITY_FTP", 17, nil, 32) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET", "MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET", 17, nil, 64) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED", "MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED", 17, nil, 128) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT", "MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT", 17, nil, 256) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_TERRAIN = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_TERRAIN", "MAV_PROTOCOL_CAPABILITY_TERRAIN", 17, nil, 512) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET", "MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET", 17, nil, 1024) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION", "MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION", 17, nil, 2048) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION", "MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION", 17, nil, 4096) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MAVLINK2 = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MAVLINK2", "MAV_PROTOCOL_CAPABILITY_MAVLINK2", 17, nil, 8192) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_FENCE = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_FENCE", "MAV_PROTOCOL_CAPABILITY_MISSION_FENCE", 17, nil, 16384) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_MISSION_RALLY = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_MISSION_RALLY", "MAV_PROTOCOL_CAPABILITY_MISSION_RALLY", 17, nil, 32768) +f.AUTOPILOT_VERSION_capabilities_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION = ProtoField.bool("mavlink_proto.AUTOPILOT_VERSION_capabilities.MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION", "MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION", 17, nil, 65536) f.AUTOPILOT_VERSION_flight_sw_version = ProtoField.new("flight_sw_version (uint32_t)", "mavlink_proto.AUTOPILOT_VERSION_flight_sw_version", ftypes.UINT32, nil) f.AUTOPILOT_VERSION_middleware_sw_version = ProtoField.new("middleware_sw_version (uint32_t)", "mavlink_proto.AUTOPILOT_VERSION_middleware_sw_version", ftypes.UINT32, nil) f.AUTOPILOT_VERSION_os_sw_version = ProtoField.new("os_sw_version (uint32_t)", "mavlink_proto.AUTOPILOT_VERSION_os_sw_version", ftypes.UINT32, nil) @@ -7532,18 +7580,18 @@ f.EFI_STATUS_fuel_pressure = ProtoField.new("fuel_pressure (float)", "mavlink_pr f.ESTIMATOR_STATUS_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.ESTIMATOR_STATUS_time_usec", ftypes.UINT64, nil) f.ESTIMATOR_STATUS_flags = ProtoField.new("flags (ESTIMATOR_STATUS_FLAGS)", "mavlink_proto.ESTIMATOR_STATUS_flags", ftypes.UINT16, nil) -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_ATTITUDE = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_ATTITUDE", "ESTIMATOR_ATTITUDE") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_VELOCITY_HORIZ = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_VELOCITY_HORIZ", "ESTIMATOR_VELOCITY_HORIZ") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_VELOCITY_VERT = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_VELOCITY_VERT", "ESTIMATOR_VELOCITY_VERT") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_HORIZ_REL", "ESTIMATOR_POS_HORIZ_REL") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_HORIZ_ABS", "ESTIMATOR_POS_HORIZ_ABS") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_VERT_ABS = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_VERT_ABS", "ESTIMATOR_POS_VERT_ABS") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_VERT_AGL = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_VERT_AGL", "ESTIMATOR_POS_VERT_AGL") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_CONST_POS_MODE = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_CONST_POS_MODE", "ESTIMATOR_CONST_POS_MODE") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_PRED_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_PRED_POS_HORIZ_REL", "ESTIMATOR_PRED_POS_HORIZ_REL") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_PRED_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_PRED_POS_HORIZ_ABS", "ESTIMATOR_PRED_POS_HORIZ_ABS") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_GPS_GLITCH = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_GPS_GLITCH", "ESTIMATOR_GPS_GLITCH") -f.ESTIMATOR_STATUS_flags_flagESTIMATOR_ACCEL_ERROR = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_ACCEL_ERROR", "ESTIMATOR_ACCEL_ERROR") +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_ATTITUDE = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_ATTITUDE", "ESTIMATOR_ATTITUDE", 12, nil, 1) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_VELOCITY_HORIZ = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_VELOCITY_HORIZ", "ESTIMATOR_VELOCITY_HORIZ", 12, nil, 2) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_VELOCITY_VERT = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_VELOCITY_VERT", "ESTIMATOR_VELOCITY_VERT", 12, nil, 4) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_HORIZ_REL", "ESTIMATOR_POS_HORIZ_REL", 12, nil, 8) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_HORIZ_ABS", "ESTIMATOR_POS_HORIZ_ABS", 12, nil, 16) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_VERT_ABS = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_VERT_ABS", "ESTIMATOR_POS_VERT_ABS", 12, nil, 32) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_POS_VERT_AGL = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_POS_VERT_AGL", "ESTIMATOR_POS_VERT_AGL", 12, nil, 64) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_CONST_POS_MODE = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_CONST_POS_MODE", "ESTIMATOR_CONST_POS_MODE", 12, nil, 128) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_PRED_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_PRED_POS_HORIZ_REL", "ESTIMATOR_PRED_POS_HORIZ_REL", 12, nil, 256) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_PRED_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_PRED_POS_HORIZ_ABS", "ESTIMATOR_PRED_POS_HORIZ_ABS", 12, nil, 512) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_GPS_GLITCH = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_GPS_GLITCH", "ESTIMATOR_GPS_GLITCH", 12, nil, 1024) +f.ESTIMATOR_STATUS_flags_flagESTIMATOR_ACCEL_ERROR = ProtoField.bool("mavlink_proto.ESTIMATOR_STATUS_flags.ESTIMATOR_ACCEL_ERROR", "ESTIMATOR_ACCEL_ERROR", 12, nil, 2048) f.ESTIMATOR_STATUS_vel_ratio = ProtoField.new("vel_ratio (float)", "mavlink_proto.ESTIMATOR_STATUS_vel_ratio", ftypes.FLOAT, nil) f.ESTIMATOR_STATUS_pos_horiz_ratio = ProtoField.new("pos_horiz_ratio (float)", "mavlink_proto.ESTIMATOR_STATUS_pos_horiz_ratio", ftypes.FLOAT, nil) f.ESTIMATOR_STATUS_pos_vert_ratio = ProtoField.new("pos_vert_ratio (float)", "mavlink_proto.ESTIMATOR_STATUS_pos_vert_ratio", ftypes.FLOAT, nil) @@ -7566,14 +7614,14 @@ f.WIND_COV_vert_accuracy = ProtoField.new("vert_accuracy (float)", "mavlink_prot f.GPS_INPUT_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.GPS_INPUT_time_usec", ftypes.UINT64, nil) f.GPS_INPUT_gps_id = ProtoField.new("gps_id (uint8_t)", "mavlink_proto.GPS_INPUT_gps_id", ftypes.UINT8, nil) f.GPS_INPUT_ignore_flags = ProtoField.new("ignore_flags (GPS_INPUT_IGNORE_FLAGS)", "mavlink_proto.GPS_INPUT_ignore_flags", ftypes.UINT16, nil) -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_ALT = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_ALT", "GPS_INPUT_IGNORE_FLAG_ALT") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_HDOP = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_HDOP", "GPS_INPUT_IGNORE_FLAG_HDOP") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VDOP = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VDOP", "GPS_INPUT_IGNORE_FLAG_VDOP") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VEL_HORIZ = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VEL_HORIZ", "GPS_INPUT_IGNORE_FLAG_VEL_HORIZ") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VEL_VERT = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VEL_VERT", "GPS_INPUT_IGNORE_FLAG_VEL_VERT") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY", "GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY", "GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY") -f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY", "GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY") +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_ALT = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_ALT", "GPS_INPUT_IGNORE_FLAG_ALT", 8, nil, 1) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_HDOP = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_HDOP", "GPS_INPUT_IGNORE_FLAG_HDOP", 8, nil, 2) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VDOP = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VDOP", "GPS_INPUT_IGNORE_FLAG_VDOP", 8, nil, 4) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VEL_HORIZ = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VEL_HORIZ", "GPS_INPUT_IGNORE_FLAG_VEL_HORIZ", 8, nil, 8) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VEL_VERT = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VEL_VERT", "GPS_INPUT_IGNORE_FLAG_VEL_VERT", 8, nil, 16) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY", "GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY", 8, nil, 32) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY", "GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY", 8, nil, 64) +f.GPS_INPUT_ignore_flags_flagGPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = ProtoField.bool("mavlink_proto.GPS_INPUT_ignore_flags.GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY", "GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY", 8, nil, 128) f.GPS_INPUT_time_week_ms = ProtoField.new("time_week_ms (uint32_t)", "mavlink_proto.GPS_INPUT_time_week_ms", ftypes.UINT32, nil) f.GPS_INPUT_time_week = ProtoField.new("time_week (uint16_t)", "mavlink_proto.GPS_INPUT_time_week", ftypes.UINT16, nil) f.GPS_INPUT_fix_type = ProtoField.new("fix_type (uint8_t)", "mavlink_proto.GPS_INPUT_fix_type", ftypes.UINT8, nil) @@ -7775,14 +7823,14 @@ f.GPS_RTCM_DATA_data_178 = ProtoField.new("data[178] (uint8_t)", "mavlink_proto. f.GPS_RTCM_DATA_data_179 = ProtoField.new("data[179] (uint8_t)", "mavlink_proto.GPS_RTCM_DATA_data_179", ftypes.UINT8, nil) f.HIGH_LATENCY_base_mode = ProtoField.new("base_mode (MAV_MODE_FLAG)", "mavlink_proto.HIGH_LATENCY_base_mode", ftypes.UINT8, nil) -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED") -f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED") +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", 8, nil, 1) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED", 8, nil, 2) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED", 8, nil, 4) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED", 8, nil, 8) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED", 8, nil, 16) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED", 8, nil, 32) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", 8, nil, 64) +f.HIGH_LATENCY_base_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HIGH_LATENCY_base_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED", 8, nil, 128) f.HIGH_LATENCY_custom_mode = ProtoField.new("custom_mode (uint32_t)", "mavlink_proto.HIGH_LATENCY_custom_mode", ftypes.UINT32, nil) f.HIGH_LATENCY_landed_state = ProtoField.new("landed_state (MAV_LANDED_STATE)", "mavlink_proto.HIGH_LATENCY_landed_state", ftypes.UINT8, enumEntryName.MAV_LANDED_STATE) f.HIGH_LATENCY_roll = ProtoField.new("roll (int16_t)", "mavlink_proto.HIGH_LATENCY_roll", ftypes.INT16, nil) @@ -7831,20 +7879,20 @@ f.HIGH_LATENCY2_climb_rate = ProtoField.new("climb_rate (int8_t)", "mavlink_prot f.HIGH_LATENCY2_battery = ProtoField.new("battery (int8_t)", "mavlink_proto.HIGH_LATENCY2_battery", ftypes.INT8, nil) f.HIGH_LATENCY2_wp_num = ProtoField.new("wp_num (uint16_t)", "mavlink_proto.HIGH_LATENCY2_wp_num", ftypes.UINT16, nil) f.HIGH_LATENCY2_failure_flags = ProtoField.new("failure_flags (HL_FAILURE_FLAG)", "mavlink_proto.HIGH_LATENCY2_failure_flags", ftypes.UINT16, nil) -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_GPS = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_GPS", "HL_FAILURE_FLAG_GPS") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE", "HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_ABSOLUTE_PRESSURE", "HL_FAILURE_FLAG_ABSOLUTE_PRESSURE") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_3D_ACCEL = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_3D_ACCEL", "HL_FAILURE_FLAG_3D_ACCEL") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_3D_GYRO = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_3D_GYRO", "HL_FAILURE_FLAG_3D_GYRO") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_3D_MAG = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_3D_MAG", "HL_FAILURE_FLAG_3D_MAG") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_TERRAIN = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_TERRAIN", "HL_FAILURE_FLAG_TERRAIN") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_BATTERY = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_BATTERY", "HL_FAILURE_FLAG_BATTERY") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_RC_RECEIVER = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_RC_RECEIVER", "HL_FAILURE_FLAG_RC_RECEIVER") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_OFFBOARD_LINK = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_OFFBOARD_LINK", "HL_FAILURE_FLAG_OFFBOARD_LINK") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_ENGINE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_ENGINE", "HL_FAILURE_FLAG_ENGINE") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_GEOFENCE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_GEOFENCE", "HL_FAILURE_FLAG_GEOFENCE") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_ESTIMATOR = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_ESTIMATOR", "HL_FAILURE_FLAG_ESTIMATOR") -f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_MISSION = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_MISSION", "HL_FAILURE_FLAG_MISSION") +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_GPS = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_GPS", "HL_FAILURE_FLAG_GPS", 14, nil, 1) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE", "HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE", 14, nil, 2) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_ABSOLUTE_PRESSURE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_ABSOLUTE_PRESSURE", "HL_FAILURE_FLAG_ABSOLUTE_PRESSURE", 14, nil, 4) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_3D_ACCEL = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_3D_ACCEL", "HL_FAILURE_FLAG_3D_ACCEL", 14, nil, 8) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_3D_GYRO = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_3D_GYRO", "HL_FAILURE_FLAG_3D_GYRO", 14, nil, 16) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_3D_MAG = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_3D_MAG", "HL_FAILURE_FLAG_3D_MAG", 14, nil, 32) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_TERRAIN = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_TERRAIN", "HL_FAILURE_FLAG_TERRAIN", 14, nil, 64) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_BATTERY = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_BATTERY", "HL_FAILURE_FLAG_BATTERY", 14, nil, 128) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_RC_RECEIVER = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_RC_RECEIVER", "HL_FAILURE_FLAG_RC_RECEIVER", 14, nil, 256) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_OFFBOARD_LINK = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_OFFBOARD_LINK", "HL_FAILURE_FLAG_OFFBOARD_LINK", 14, nil, 512) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_ENGINE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_ENGINE", "HL_FAILURE_FLAG_ENGINE", 14, nil, 1024) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_GEOFENCE = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_GEOFENCE", "HL_FAILURE_FLAG_GEOFENCE", 14, nil, 2048) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_ESTIMATOR = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_ESTIMATOR", "HL_FAILURE_FLAG_ESTIMATOR", 14, nil, 4096) +f.HIGH_LATENCY2_failure_flags_flagHL_FAILURE_FLAG_MISSION = ProtoField.bool("mavlink_proto.HIGH_LATENCY2_failure_flags.HL_FAILURE_FLAG_MISSION", "HL_FAILURE_FLAG_MISSION", 14, nil, 8192) f.HIGH_LATENCY2_custom0 = ProtoField.new("custom0 (int8_t)", "mavlink_proto.HIGH_LATENCY2_custom0", ftypes.INT8, nil) f.HIGH_LATENCY2_custom1 = ProtoField.new("custom1 (int8_t)", "mavlink_proto.HIGH_LATENCY2_custom1", ftypes.INT8, nil) f.HIGH_LATENCY2_custom2 = ProtoField.new("custom2 (int8_t)", "mavlink_proto.HIGH_LATENCY2_custom2", ftypes.INT8, nil) @@ -7906,16 +7954,16 @@ f.ADSB_VEHICLE_callsign = ProtoField.new("callsign (char)", "mavlink_proto.ADSB_ f.ADSB_VEHICLE_emitter_type = ProtoField.new("emitter_type (ADSB_EMITTER_TYPE)", "mavlink_proto.ADSB_VEHICLE_emitter_type", ftypes.UINT8, enumEntryName.ADSB_EMITTER_TYPE) f.ADSB_VEHICLE_tslc = ProtoField.new("tslc (uint8_t)", "mavlink_proto.ADSB_VEHICLE_tslc", ftypes.UINT8, nil) f.ADSB_VEHICLE_flags = ProtoField.new("flags (ADSB_FLAGS)", "mavlink_proto.ADSB_VEHICLE_flags", ftypes.UINT16, nil) -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_COORDS = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_COORDS", "ADSB_FLAGS_VALID_COORDS") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_ALTITUDE = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_ALTITUDE", "ADSB_FLAGS_VALID_ALTITUDE") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_HEADING = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_HEADING", "ADSB_FLAGS_VALID_HEADING") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_VELOCITY = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_VELOCITY", "ADSB_FLAGS_VALID_VELOCITY") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_CALLSIGN = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_CALLSIGN", "ADSB_FLAGS_VALID_CALLSIGN") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_SQUAWK = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_SQUAWK", "ADSB_FLAGS_VALID_SQUAWK") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_SIMULATED = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_SIMULATED", "ADSB_FLAGS_SIMULATED") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VERTICAL_VELOCITY_VALID = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VERTICAL_VELOCITY_VALID", "ADSB_FLAGS_VERTICAL_VELOCITY_VALID") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_BARO_VALID = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_BARO_VALID", "ADSB_FLAGS_BARO_VALID") -f.ADSB_VEHICLE_flags_flagADSB_FLAGS_SOURCE_UAT = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_SOURCE_UAT", "ADSB_FLAGS_SOURCE_UAT") +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_COORDS = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_COORDS", "ADSB_FLAGS_VALID_COORDS", 16, nil, 1) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_ALTITUDE = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_ALTITUDE", "ADSB_FLAGS_VALID_ALTITUDE", 16, nil, 2) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_HEADING = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_HEADING", "ADSB_FLAGS_VALID_HEADING", 16, nil, 4) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_VELOCITY = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_VELOCITY", "ADSB_FLAGS_VALID_VELOCITY", 16, nil, 8) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_CALLSIGN = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_CALLSIGN", "ADSB_FLAGS_VALID_CALLSIGN", 16, nil, 16) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VALID_SQUAWK = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VALID_SQUAWK", "ADSB_FLAGS_VALID_SQUAWK", 16, nil, 32) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_SIMULATED = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_SIMULATED", "ADSB_FLAGS_SIMULATED", 16, nil, 64) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_VERTICAL_VELOCITY_VALID = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_VERTICAL_VELOCITY_VALID", "ADSB_FLAGS_VERTICAL_VELOCITY_VALID", 16, nil, 128) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_BARO_VALID = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_BARO_VALID", "ADSB_FLAGS_BARO_VALID", 16, nil, 256) +f.ADSB_VEHICLE_flags_flagADSB_FLAGS_SOURCE_UAT = ProtoField.bool("mavlink_proto.ADSB_VEHICLE_flags.ADSB_FLAGS_SOURCE_UAT", "ADSB_FLAGS_SOURCE_UAT", 16, nil, 32768) f.ADSB_VEHICLE_squawk = ProtoField.new("squawk (uint16_t)", "mavlink_proto.ADSB_VEHICLE_squawk", ftypes.UINT16, nil) f.COLLISION_src = ProtoField.new("src (MAV_COLLISION_SRC)", "mavlink_proto.COLLISION_src", ftypes.UINT8, enumEntryName.MAV_COLLISION_SRC) @@ -8357,18 +8405,18 @@ f.CAMERA_INFORMATION_resolution_h = ProtoField.new("resolution_h (uint16_t)", "m f.CAMERA_INFORMATION_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.CAMERA_INFORMATION_resolution_v", ftypes.UINT16, nil) f.CAMERA_INFORMATION_lens_id = ProtoField.new("lens_id (uint8_t)", "mavlink_proto.CAMERA_INFORMATION_lens_id", ftypes.UINT8, nil) f.CAMERA_INFORMATION_flags = ProtoField.new("flags (CAMERA_CAP_FLAGS)", "mavlink_proto.CAMERA_INFORMATION_flags", ftypes.UINT32, nil) -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAPTURE_VIDEO = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAPTURE_VIDEO", "CAMERA_CAP_FLAGS_CAPTURE_VIDEO") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAPTURE_IMAGE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAPTURE_IMAGE", "CAMERA_CAP_FLAGS_CAPTURE_IMAGE") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_MODES = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_MODES", "CAMERA_CAP_FLAGS_HAS_MODES") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE", "CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE", "CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE", "CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM", "CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS", "CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM", "CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_POINT = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_POINT", "CAMERA_CAP_FLAGS_HAS_TRACKING_POINT") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE", "CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE") -f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS", "CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS") +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAPTURE_VIDEO = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAPTURE_VIDEO", "CAMERA_CAP_FLAGS_CAPTURE_VIDEO", 12, nil, 1) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAPTURE_IMAGE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAPTURE_IMAGE", "CAMERA_CAP_FLAGS_CAPTURE_IMAGE", 12, nil, 2) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_MODES = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_MODES", "CAMERA_CAP_FLAGS_HAS_MODES", 12, nil, 4) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE", "CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE", 12, nil, 8) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE", "CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE", 12, nil, 16) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE", "CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE", 12, nil, 32) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM", "CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM", 12, nil, 64) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS", "CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS", 12, nil, 128) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM", "CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM", 12, nil, 256) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_POINT = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_POINT", "CAMERA_CAP_FLAGS_HAS_TRACKING_POINT", 12, nil, 512) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE", "CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE", 12, nil, 1024) +f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = ProtoField.bool("mavlink_proto.CAMERA_INFORMATION_flags.CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS", "CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS", 12, nil, 2048) f.CAMERA_INFORMATION_cam_definition_version = ProtoField.new("cam_definition_version (uint16_t)", "mavlink_proto.CAMERA_INFORMATION_cam_definition_version", ftypes.UINT16, nil) f.CAMERA_INFORMATION_cam_definition_uri = ProtoField.new("cam_definition_uri (char)", "mavlink_proto.CAMERA_INFORMATION_cam_definition_uri", ftypes.STRING, nil) @@ -8941,8 +8989,8 @@ f.VIDEO_STREAM_INFORMATION_stream_id = ProtoField.new("stream_id (uint8_t)", "ma f.VIDEO_STREAM_INFORMATION_count = ProtoField.new("count (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION_count", ftypes.UINT8, nil) f.VIDEO_STREAM_INFORMATION_type = ProtoField.new("type (VIDEO_STREAM_TYPE)", "mavlink_proto.VIDEO_STREAM_INFORMATION_type", ftypes.UINT8, enumEntryName.VIDEO_STREAM_TYPE) f.VIDEO_STREAM_INFORMATION_flags = ProtoField.new("flags (VIDEO_STREAM_STATUS_FLAGS)", "mavlink_proto.VIDEO_STREAM_INFORMATION_flags", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION_flags_flagVIDEO_STREAM_STATUS_FLAGS_RUNNING = ProtoField.bool("mavlink_proto.VIDEO_STREAM_INFORMATION_flags.VIDEO_STREAM_STATUS_FLAGS_RUNNING", "VIDEO_STREAM_STATUS_FLAGS_RUNNING") -f.VIDEO_STREAM_INFORMATION_flags_flagVIDEO_STREAM_STATUS_FLAGS_THERMAL = ProtoField.bool("mavlink_proto.VIDEO_STREAM_INFORMATION_flags.VIDEO_STREAM_STATUS_FLAGS_THERMAL", "VIDEO_STREAM_STATUS_FLAGS_THERMAL") +f.VIDEO_STREAM_INFORMATION_flags_flagVIDEO_STREAM_STATUS_FLAGS_RUNNING = ProtoField.bool("mavlink_proto.VIDEO_STREAM_INFORMATION_flags.VIDEO_STREAM_STATUS_FLAGS_RUNNING", "VIDEO_STREAM_STATUS_FLAGS_RUNNING", 2, nil, 1) +f.VIDEO_STREAM_INFORMATION_flags_flagVIDEO_STREAM_STATUS_FLAGS_THERMAL = ProtoField.bool("mavlink_proto.VIDEO_STREAM_INFORMATION_flags.VIDEO_STREAM_STATUS_FLAGS_THERMAL", "VIDEO_STREAM_STATUS_FLAGS_THERMAL", 2, nil, 2) f.VIDEO_STREAM_INFORMATION_framerate = ProtoField.new("framerate (float)", "mavlink_proto.VIDEO_STREAM_INFORMATION_framerate", ftypes.FLOAT, nil) f.VIDEO_STREAM_INFORMATION_resolution_h = ProtoField.new("resolution_h (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION_resolution_h", ftypes.UINT16, nil) f.VIDEO_STREAM_INFORMATION_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION_resolution_v", ftypes.UINT16, nil) @@ -8954,8 +9002,8 @@ f.VIDEO_STREAM_INFORMATION_uri = ProtoField.new("uri (char)", "mavlink_proto.VID f.VIDEO_STREAM_STATUS_stream_id = ProtoField.new("stream_id (uint8_t)", "mavlink_proto.VIDEO_STREAM_STATUS_stream_id", ftypes.UINT8, nil) f.VIDEO_STREAM_STATUS_flags = ProtoField.new("flags (VIDEO_STREAM_STATUS_FLAGS)", "mavlink_proto.VIDEO_STREAM_STATUS_flags", ftypes.UINT16, nil) -f.VIDEO_STREAM_STATUS_flags_flagVIDEO_STREAM_STATUS_FLAGS_RUNNING = ProtoField.bool("mavlink_proto.VIDEO_STREAM_STATUS_flags.VIDEO_STREAM_STATUS_FLAGS_RUNNING", "VIDEO_STREAM_STATUS_FLAGS_RUNNING") -f.VIDEO_STREAM_STATUS_flags_flagVIDEO_STREAM_STATUS_FLAGS_THERMAL = ProtoField.bool("mavlink_proto.VIDEO_STREAM_STATUS_flags.VIDEO_STREAM_STATUS_FLAGS_THERMAL", "VIDEO_STREAM_STATUS_FLAGS_THERMAL") +f.VIDEO_STREAM_STATUS_flags_flagVIDEO_STREAM_STATUS_FLAGS_RUNNING = ProtoField.bool("mavlink_proto.VIDEO_STREAM_STATUS_flags.VIDEO_STREAM_STATUS_FLAGS_RUNNING", "VIDEO_STREAM_STATUS_FLAGS_RUNNING", 2, nil, 1) +f.VIDEO_STREAM_STATUS_flags_flagVIDEO_STREAM_STATUS_FLAGS_THERMAL = ProtoField.bool("mavlink_proto.VIDEO_STREAM_STATUS_flags.VIDEO_STREAM_STATUS_FLAGS_THERMAL", "VIDEO_STREAM_STATUS_FLAGS_THERMAL", 2, nil, 2) f.VIDEO_STREAM_STATUS_framerate = ProtoField.new("framerate (float)", "mavlink_proto.VIDEO_STREAM_STATUS_framerate", ftypes.FLOAT, nil) f.VIDEO_STREAM_STATUS_resolution_h = ProtoField.new("resolution_h (uint16_t)", "mavlink_proto.VIDEO_STREAM_STATUS_resolution_h", ftypes.UINT16, nil) f.VIDEO_STREAM_STATUS_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.VIDEO_STREAM_STATUS_resolution_v", ftypes.UINT16, nil) @@ -8979,7 +9027,10 @@ f.CAMERA_FOV_STATUS_vfov = ProtoField.new("vfov (float)", "mavlink_proto.CAMERA_ f.CAMERA_TRACKING_IMAGE_STATUS_tracking_status = ProtoField.new("tracking_status (CAMERA_TRACKING_STATUS_FLAGS)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_tracking_status", ftypes.UINT8, enumEntryName.CAMERA_TRACKING_STATUS_FLAGS) f.CAMERA_TRACKING_IMAGE_STATUS_tracking_mode = ProtoField.new("tracking_mode (CAMERA_TRACKING_MODE)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_tracking_mode", ftypes.UINT8, enumEntryName.CAMERA_TRACKING_MODE) -f.CAMERA_TRACKING_IMAGE_STATUS_target_data = ProtoField.new("target_data (CAMERA_TRACKING_TARGET_DATA)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_target_data", ftypes.UINT8, enumEntryName.CAMERA_TRACKING_TARGET_DATA) +f.CAMERA_TRACKING_IMAGE_STATUS_target_data = ProtoField.new("target_data (CAMERA_TRACKING_TARGET_DATA)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_target_data", ftypes.UINT8, nil) +f.CAMERA_TRACKING_IMAGE_STATUS_target_data_flagCAMERA_TRACKING_TARGET_DATA_EMBEDDED = ProtoField.bool("mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_target_data.CAMERA_TRACKING_TARGET_DATA_EMBEDDED", "CAMERA_TRACKING_TARGET_DATA_EMBEDDED", 3, nil, 1) +f.CAMERA_TRACKING_IMAGE_STATUS_target_data_flagCAMERA_TRACKING_TARGET_DATA_RENDERED = ProtoField.bool("mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_target_data.CAMERA_TRACKING_TARGET_DATA_RENDERED", "CAMERA_TRACKING_TARGET_DATA_RENDERED", 3, nil, 2) +f.CAMERA_TRACKING_IMAGE_STATUS_target_data_flagCAMERA_TRACKING_TARGET_DATA_IN_STATUS = ProtoField.bool("mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_target_data.CAMERA_TRACKING_TARGET_DATA_IN_STATUS", "CAMERA_TRACKING_TARGET_DATA_IN_STATUS", 3, nil, 4) f.CAMERA_TRACKING_IMAGE_STATUS_point_x = ProtoField.new("point_x (float)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_point_x", ftypes.FLOAT, nil) f.CAMERA_TRACKING_IMAGE_STATUS_point_y = ProtoField.new("point_y (float)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_point_y", ftypes.FLOAT, nil) f.CAMERA_TRACKING_IMAGE_STATUS_radius = ProtoField.new("radius (float)", "mavlink_proto.CAMERA_TRACKING_IMAGE_STATUS_radius", ftypes.FLOAT, nil) @@ -9002,6 +9053,45 @@ f.CAMERA_TRACKING_GEO_STATUS_dist = ProtoField.new("dist (float)", "mavlink_prot f.CAMERA_TRACKING_GEO_STATUS_hdg = ProtoField.new("hdg (float)", "mavlink_proto.CAMERA_TRACKING_GEO_STATUS_hdg", ftypes.FLOAT, nil) f.CAMERA_TRACKING_GEO_STATUS_hdg_acc = ProtoField.new("hdg_acc (float)", "mavlink_proto.CAMERA_TRACKING_GEO_STATUS_hdg_acc", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_INFORMATION_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_time_boot_ms", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_INFORMATION_cap_flags = ProtoField.new("cap_flags (GIMBAL_MANAGER_CAP_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT", "GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT", 18, nil, 1) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL", "GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL", 18, nil, 2) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS", "GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS", 18, nil, 4) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW", "GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW", 18, nil, 8) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK", "GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK", 18, nil, 16) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS", "GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS", 18, nil, 32) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW", "GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW", 18, nil, 64) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK", "GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK", 18, nil, 128) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS", "GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS", 18, nil, 256) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW", "GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW", 18, nil, 512) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK", "GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK", 18, nil, 1024) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW", "GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW", 18, nil, 2048) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", 18, nil, 4096) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS", "GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS", 18, nil, 8192) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL", "GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL", 18, nil, 65536) +f.GIMBAL_MANAGER_INFORMATION_cap_flags_flagGIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_INFORMATION_cap_flags.GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL", "GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL", 18, nil, 131072) +f.GIMBAL_MANAGER_INFORMATION_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_gimbal_device_id", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_INFORMATION_roll_min = ProtoField.new("roll_min (float)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_roll_min", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_INFORMATION_roll_max = ProtoField.new("roll_max (float)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_roll_max", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_INFORMATION_pitch_min = ProtoField.new("pitch_min (float)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_pitch_min", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_INFORMATION_pitch_max = ProtoField.new("pitch_max (float)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_pitch_max", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_INFORMATION_yaw_min = ProtoField.new("yaw_min (float)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_yaw_min", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlink_proto.GIMBAL_MANAGER_INFORMATION_yaw_max", ftypes.FLOAT, nil) + +f.GIMBAL_MANAGER_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_time_boot_ms", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_STATUS_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_STATUS_flags", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) +f.GIMBAL_MANAGER_STATUS_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_gimbal_device_id", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_STATUS_primary_control_sysid = ProtoField.new("primary_control_sysid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_primary_control_sysid", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_STATUS_primary_control_compid = ProtoField.new("primary_control_compid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_primary_control_compid", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_STATUS_secondary_control_sysid = ProtoField.new("secondary_control_sysid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_secondary_control_sysid", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_STATUS_secondary_control_compid = ProtoField.new("secondary_control_compid (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_STATUS_secondary_control_compid", ftypes.UINT8, nil) + f.GIMBAL_DEVICE_INFORMATION_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_time_boot_ms", ftypes.UINT32, nil) f.GIMBAL_DEVICE_INFORMATION_vendor_name = ProtoField.new("vendor_name (char)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_vendor_name", ftypes.STRING, nil) f.GIMBAL_DEVICE_INFORMATION_model_name = ProtoField.new("model_name (char)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_model_name", ftypes.STRING, nil) @@ -9010,18 +9100,18 @@ f.GIMBAL_DEVICE_INFORMATION_firmware_version = ProtoField.new("firmware_version f.GIMBAL_DEVICE_INFORMATION_hardware_version = ProtoField.new("hardware_version (uint32_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_hardware_version", ftypes.UINT32, nil) f.GIMBAL_DEVICE_INFORMATION_uid = ProtoField.new("uid (uint64_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_uid", ftypes.UINT64, nil) f.GIMBAL_DEVICE_INFORMATION_cap_flags = ProtoField.new("cap_flags (GIMBAL_DEVICE_CAP_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags", ftypes.UINT16, nil) -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", "GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", "GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK") -f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW") +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", "GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT", 12, nil, 1) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", "GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL", 12, nil, 2) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS", 12, nil, 4) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW", 12, nil, 8) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK", 12, nil, 16) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS", 12, nil, 32) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW", 12, nil, 64) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK", 12, nil, 128) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS", 12, nil, 256) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", 12, nil, 512) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", 12, nil, 1024) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", 12, nil, 2048) f.GIMBAL_DEVICE_INFORMATION_custom_cap_flags = ProtoField.new("custom_cap_flags (uint16_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_custom_cap_flags", ftypes.UINT16, nil) f.GIMBAL_DEVICE_INFORMATION_roll_min = ProtoField.new("roll_min (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_roll_min", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_INFORMATION_roll_max = ProtoField.new("roll_max (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_roll_max", ftypes.FLOAT, nil) @@ -9033,11 +9123,11 @@ f.GIMBAL_DEVICE_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlink f.GIMBAL_DEVICE_SET_ATTITUDE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_target_system", ftypes.UINT8, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_target_component", ftypes.UINT8, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_flags = ProtoField.new("flags (GIMBAL_DEVICE_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags", ftypes.UINT16, nil) -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT") -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL") -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK") -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK") -f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK") +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 5, nil, 1) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL", 5, nil, 2) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 5, nil, 4) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 5, nil, 8) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK", 5, nil, 16) f.GIMBAL_DEVICE_SET_ATTITUDE_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_q_0", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_q_1", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_SET_ATTITUDE_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_q_2", ftypes.FLOAT, nil) @@ -9050,11 +9140,11 @@ f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_system = ProtoField.new("target_system (u f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_target_component", ftypes.UINT8, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_time_boot_ms", ftypes.UINT32, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags = ProtoField.new("flags (GIMBAL_DEVICE_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags", ftypes.UINT16, nil) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK") +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 5, nil, 1) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_NEUTRAL", "GIMBAL_DEVICE_FLAGS_NEUTRAL", 5, nil, 2) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_ROLL_LOCK", "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", 5, nil, 4) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_PITCH_LOCK", "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", 5, nil, 8) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_LOCK", "GIMBAL_DEVICE_FLAGS_YAW_LOCK", 5, nil, 16) f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_q_0", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_q_1", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_q_2", ftypes.FLOAT, nil) @@ -9063,15 +9153,15 @@ f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_x = ProtoField.new("angular_vel f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_y", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_z", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags = ProtoField.new("failure_flags (GIMBAL_DEVICE_ERROR_FLAGS)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags", ftypes.UINT32, nil) -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR") -f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING") +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", 9, nil, 1) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT", 9, nil, 2) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", "GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT", 9, nil, 4) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR", 9, nil, 8) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR", 9, nil, 16) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR", 9, nil, 32) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", 9, nil, 64) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", 9, nil, 128) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", 9, nil, 256) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_system", ftypes.UINT8, nil) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_component", ftypes.UINT8, nil) @@ -9087,28 +9177,28 @@ f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vz = ProtoField.new("vz (float)", "mavlink_p f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_v_estimated_delay_us = ProtoField.new("v_estimated_delay_us (uint32_t)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_v_estimated_delay_us", ftypes.UINT32, nil) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_feed_forward_angular_velocity_z = ProtoField.new("feed_forward_angular_velocity_z (float)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_feed_forward_angular_velocity_z", ftypes.FLOAT, nil) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status = ProtoField.new("estimator_status (ESTIMATOR_STATUS_FLAGS)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status", ftypes.UINT16, nil) -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_ATTITUDE = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_ATTITUDE", "ESTIMATOR_ATTITUDE") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_VELOCITY_HORIZ = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_VELOCITY_HORIZ", "ESTIMATOR_VELOCITY_HORIZ") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_VELOCITY_VERT = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_VELOCITY_VERT", "ESTIMATOR_VELOCITY_VERT") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_HORIZ_REL", "ESTIMATOR_POS_HORIZ_REL") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_HORIZ_ABS", "ESTIMATOR_POS_HORIZ_ABS") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_VERT_ABS = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_VERT_ABS", "ESTIMATOR_POS_VERT_ABS") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_VERT_AGL = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_VERT_AGL", "ESTIMATOR_POS_VERT_AGL") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_CONST_POS_MODE = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_CONST_POS_MODE", "ESTIMATOR_CONST_POS_MODE") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_PRED_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_PRED_POS_HORIZ_REL", "ESTIMATOR_PRED_POS_HORIZ_REL") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_PRED_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_PRED_POS_HORIZ_ABS", "ESTIMATOR_PRED_POS_HORIZ_ABS") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_GPS_GLITCH = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_GPS_GLITCH", "ESTIMATOR_GPS_GLITCH") -f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_ACCEL_ERROR = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_ACCEL_ERROR", "ESTIMATOR_ACCEL_ERROR") +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_ATTITUDE = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_ATTITUDE", "ESTIMATOR_ATTITUDE", 12, nil, 1) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_VELOCITY_HORIZ = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_VELOCITY_HORIZ", "ESTIMATOR_VELOCITY_HORIZ", 12, nil, 2) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_VELOCITY_VERT = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_VELOCITY_VERT", "ESTIMATOR_VELOCITY_VERT", 12, nil, 4) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_HORIZ_REL", "ESTIMATOR_POS_HORIZ_REL", 12, nil, 8) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_HORIZ_ABS", "ESTIMATOR_POS_HORIZ_ABS", 12, nil, 16) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_VERT_ABS = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_VERT_ABS", "ESTIMATOR_POS_VERT_ABS", 12, nil, 32) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_POS_VERT_AGL = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_POS_VERT_AGL", "ESTIMATOR_POS_VERT_AGL", 12, nil, 64) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_CONST_POS_MODE = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_CONST_POS_MODE", "ESTIMATOR_CONST_POS_MODE", 12, nil, 128) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_PRED_POS_HORIZ_REL = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_PRED_POS_HORIZ_REL", "ESTIMATOR_PRED_POS_HORIZ_REL", 12, nil, 256) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_PRED_POS_HORIZ_ABS = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_PRED_POS_HORIZ_ABS", "ESTIMATOR_PRED_POS_HORIZ_ABS", 12, nil, 512) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_GPS_GLITCH = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_GPS_GLITCH", "ESTIMATOR_GPS_GLITCH", 12, nil, 1024) +f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_ACCEL_ERROR = ProtoField.bool("mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status.ESTIMATOR_ACCEL_ERROR", "ESTIMATOR_ACCEL_ERROR", 12, nil, 2048) f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state = ProtoField.new("landed_state (MAV_LANDED_STATE)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state", ftypes.UINT8, enumEntryName.MAV_LANDED_STATE) f.GIMBAL_MANAGER_SET_ATTITUDE_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_target_system", ftypes.UINT8, nil) f.GIMBAL_MANAGER_SET_ATTITUDE_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_target_component", ftypes.UINT8, nil) f.GIMBAL_MANAGER_SET_ATTITUDE_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags", ftypes.UINT32, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT") -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL") -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK") -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK") -f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK") +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id", ftypes.UINT8, nil) f.GIMBAL_MANAGER_SET_ATTITUDE_q_0 = ProtoField.new("q[0] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_0", ftypes.FLOAT, nil) f.GIMBAL_MANAGER_SET_ATTITUDE_q_1 = ProtoField.new("q[1] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_1", ftypes.FLOAT, nil) @@ -9118,6 +9208,20 @@ f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x = ProtoField.new("angular_veloc f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y = ProtoField.new("angular_velocity_y (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y", ftypes.FLOAT, nil) f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_target_system", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_target_component", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 5, nil, 1) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 5, nil, 2) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 5, nil, 4) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 5, nil, 8) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 5, nil, 16) +f.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_pitch = ProtoField.new("pitch (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_pitch", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_yaw = ProtoField.new("yaw (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_yaw", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate = ProtoField.new("pitch_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate = ProtoField.new("yaw_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate", ftypes.FLOAT, nil) + f.WIFI_CONFIG_AP_ssid = ProtoField.new("ssid (char)", "mavlink_proto.WIFI_CONFIG_AP_ssid", ftypes.STRING, nil) f.WIFI_CONFIG_AP_password = ProtoField.new("password (char)", "mavlink_proto.WIFI_CONFIG_AP_password", ftypes.STRING, nil) @@ -9138,19 +9242,19 @@ f.AIS_VESSEL_callsign = ProtoField.new("callsign (char)", "mavlink_proto.AIS_VES f.AIS_VESSEL_name = ProtoField.new("name (char)", "mavlink_proto.AIS_VESSEL_name", ftypes.STRING, nil) f.AIS_VESSEL_tslc = ProtoField.new("tslc (uint16_t)", "mavlink_proto.AIS_VESSEL_tslc", ftypes.UINT16, nil) f.AIS_VESSEL_flags = ProtoField.new("flags (AIS_FLAGS)", "mavlink_proto.AIS_VESSEL_flags", ftypes.UINT16, nil) -f.AIS_VESSEL_flags_flagAIS_FLAGS_POSITION_ACCURACY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_POSITION_ACCURACY", "AIS_FLAGS_POSITION_ACCURACY") -f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_COG = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_COG", "AIS_FLAGS_VALID_COG") -f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_VELOCITY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_VELOCITY", "AIS_FLAGS_VALID_VELOCITY") -f.AIS_VESSEL_flags_flagAIS_FLAGS_HIGH_VELOCITY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_HIGH_VELOCITY", "AIS_FLAGS_HIGH_VELOCITY") -f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_TURN_RATE = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_TURN_RATE", "AIS_FLAGS_VALID_TURN_RATE") -f.AIS_VESSEL_flags_flagAIS_FLAGS_TURN_RATE_SIGN_ONLY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_TURN_RATE_SIGN_ONLY", "AIS_FLAGS_TURN_RATE_SIGN_ONLY") -f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_DIMENSIONS = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_DIMENSIONS", "AIS_FLAGS_VALID_DIMENSIONS") -f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_BOW_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_BOW_DIMENSION", "AIS_FLAGS_LARGE_BOW_DIMENSION") -f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_STERN_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_STERN_DIMENSION", "AIS_FLAGS_LARGE_STERN_DIMENSION") -f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_PORT_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_PORT_DIMENSION", "AIS_FLAGS_LARGE_PORT_DIMENSION") -f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_STARBOARD_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_STARBOARD_DIMENSION", "AIS_FLAGS_LARGE_STARBOARD_DIMENSION") -f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_CALLSIGN = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_CALLSIGN", "AIS_FLAGS_VALID_CALLSIGN") -f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_NAME = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_NAME", "AIS_FLAGS_VALID_NAME") +f.AIS_VESSEL_flags_flagAIS_FLAGS_POSITION_ACCURACY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_POSITION_ACCURACY", "AIS_FLAGS_POSITION_ACCURACY", 13, nil, 1) +f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_COG = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_COG", "AIS_FLAGS_VALID_COG", 13, nil, 2) +f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_VELOCITY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_VELOCITY", "AIS_FLAGS_VALID_VELOCITY", 13, nil, 4) +f.AIS_VESSEL_flags_flagAIS_FLAGS_HIGH_VELOCITY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_HIGH_VELOCITY", "AIS_FLAGS_HIGH_VELOCITY", 13, nil, 8) +f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_TURN_RATE = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_TURN_RATE", "AIS_FLAGS_VALID_TURN_RATE", 13, nil, 16) +f.AIS_VESSEL_flags_flagAIS_FLAGS_TURN_RATE_SIGN_ONLY = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_TURN_RATE_SIGN_ONLY", "AIS_FLAGS_TURN_RATE_SIGN_ONLY", 13, nil, 32) +f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_DIMENSIONS = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_DIMENSIONS", "AIS_FLAGS_VALID_DIMENSIONS", 13, nil, 64) +f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_BOW_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_BOW_DIMENSION", "AIS_FLAGS_LARGE_BOW_DIMENSION", 13, nil, 128) +f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_STERN_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_STERN_DIMENSION", "AIS_FLAGS_LARGE_STERN_DIMENSION", 13, nil, 256) +f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_PORT_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_PORT_DIMENSION", "AIS_FLAGS_LARGE_PORT_DIMENSION", 13, nil, 512) +f.AIS_VESSEL_flags_flagAIS_FLAGS_LARGE_STARBOARD_DIMENSION = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_LARGE_STARBOARD_DIMENSION", "AIS_FLAGS_LARGE_STARBOARD_DIMENSION", 13, nil, 1024) +f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_CALLSIGN = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_CALLSIGN", "AIS_FLAGS_VALID_CALLSIGN", 13, nil, 2048) +f.AIS_VESSEL_flags_flagAIS_FLAGS_VALID_NAME = ProtoField.bool("mavlink_proto.AIS_VESSEL_flags.AIS_FLAGS_VALID_NAME", "AIS_FLAGS_VALID_NAME", 13, nil, 4096) f.UAVCAN_NODE_STATUS_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.UAVCAN_NODE_STATUS_time_usec", ftypes.UINT64, nil) f.UAVCAN_NODE_STATUS_uptime_sec = ProtoField.new("uptime_sec (uint32_t)", "mavlink_proto.UAVCAN_NODE_STATUS_uptime_sec", ftypes.UINT32, nil) @@ -9350,6 +9454,7 @@ f.ODOMETRY_velocity_covariance_19 = ProtoField.new("velocity_covariance[19] (flo f.ODOMETRY_velocity_covariance_20 = ProtoField.new("velocity_covariance[20] (float)", "mavlink_proto.ODOMETRY_velocity_covariance_20", ftypes.FLOAT, nil) f.ODOMETRY_reset_counter = ProtoField.new("reset_counter (uint8_t)", "mavlink_proto.ODOMETRY_reset_counter", ftypes.UINT8, nil) f.ODOMETRY_estimator_type = ProtoField.new("estimator_type (MAV_ESTIMATOR_TYPE)", "mavlink_proto.ODOMETRY_estimator_type", ftypes.UINT8, enumEntryName.MAV_ESTIMATOR_TYPE) +f.ODOMETRY_quality = ProtoField.new("quality (int8_t)", "mavlink_proto.ODOMETRY_quality", ftypes.INT8, nil) f.ISBD_LINK_STATUS_timestamp = ProtoField.new("timestamp (uint64_t)", "mavlink_proto.ISBD_LINK_STATUS_timestamp", ftypes.UINT64, nil) f.ISBD_LINK_STATUS_last_heartbeat = ProtoField.new("last_heartbeat (uint64_t)", "mavlink_proto.ISBD_LINK_STATUS_last_heartbeat", ftypes.UINT64, nil) @@ -9398,14 +9503,14 @@ f.UTM_GLOBAL_POSITION_next_alt = ProtoField.new("next_alt (int32_t)", "mavlink_p f.UTM_GLOBAL_POSITION_update_rate = ProtoField.new("update_rate (uint16_t)", "mavlink_proto.UTM_GLOBAL_POSITION_update_rate", ftypes.UINT16, nil) f.UTM_GLOBAL_POSITION_flight_state = ProtoField.new("flight_state (UTM_FLIGHT_STATE)", "mavlink_proto.UTM_GLOBAL_POSITION_flight_state", ftypes.UINT8, enumEntryName.UTM_FLIGHT_STATE) f.UTM_GLOBAL_POSITION_flags = ProtoField.new("flags (UTM_DATA_AVAIL_FLAGS)", "mavlink_proto.UTM_GLOBAL_POSITION_flags", ftypes.UINT8, nil) -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_TIME_VALID = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_TIME_VALID", "UTM_DATA_AVAIL_FLAGS_TIME_VALID") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE") -f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE") +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_TIME_VALID = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_TIME_VALID", "UTM_DATA_AVAIL_FLAGS_TIME_VALID", 8, nil, 1) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE", 8, nil, 2) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE", 8, nil, 4) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE", 8, nil, 8) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE", 8, nil, 16) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE", 8, nil, 32) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE", 8, nil, 64) +f.UTM_GLOBAL_POSITION_flags_flagUTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = ProtoField.bool("mavlink_proto.UTM_GLOBAL_POSITION_flags.UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE", "UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE", 8, nil, 128) f.DEBUG_FLOAT_ARRAY_time_usec = ProtoField.new("time_usec (uint64_t)", "mavlink_proto.DEBUG_FLOAT_ARRAY_time_usec", ftypes.UINT64, nil) f.DEBUG_FLOAT_ARRAY_name = ProtoField.new("name (char)", "mavlink_proto.DEBUG_FLOAT_ARRAY_name", ftypes.STRING, nil) @@ -9488,29 +9593,29 @@ f.SMART_BATTERY_INFO_discharge_maximum_burst_current = ProtoField.new("discharge f.SMART_BATTERY_INFO_manufacture_date = ProtoField.new("manufacture_date (char)", "mavlink_proto.SMART_BATTERY_INFO_manufacture_date", ftypes.STRING, nil) f.GENERATOR_STATUS_status = ProtoField.new("status (MAV_GENERATOR_STATUS_FLAG)", "mavlink_proto.GENERATOR_STATUS_status", ftypes.UINT64, nil) -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OFF = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OFF", "MAV_GENERATOR_STATUS_FLAG_OFF") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_READY = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_READY", "MAV_GENERATOR_STATUS_FLAG_READY") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_GENERATING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_GENERATING", "MAV_GENERATOR_STATUS_FLAG_GENERATING") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_CHARGING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_CHARGING", "MAV_GENERATOR_STATUS_FLAG_CHARGING") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER", "MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_MAXPOWER = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_MAXPOWER", "MAV_GENERATOR_STATUS_FLAG_MAXPOWER") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING", "MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT", "MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING", "MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT", "MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT", "MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT", "MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING", "MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING", "MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT", "MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT", "MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT", "MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT", "MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT", "MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_START_INHIBITED = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_START_INHIBITED", "MAV_GENERATOR_STATUS_FLAG_START_INHIBITED") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED", "MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_WARMING_UP = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_WARMING_UP", "MAV_GENERATOR_STATUS_FLAG_WARMING_UP") -f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_IDLE = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_IDLE", "MAV_GENERATOR_STATUS_FLAG_IDLE") +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OFF = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OFF", "MAV_GENERATOR_STATUS_FLAG_OFF", 23, nil, 1) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_READY = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_READY", "MAV_GENERATOR_STATUS_FLAG_READY", 23, nil, 2) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_GENERATING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_GENERATING", "MAV_GENERATOR_STATUS_FLAG_GENERATING", 23, nil, 4) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_CHARGING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_CHARGING", "MAV_GENERATOR_STATUS_FLAG_CHARGING", 23, nil, 8) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER", "MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER", 23, nil, 16) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_MAXPOWER = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_MAXPOWER", "MAV_GENERATOR_STATUS_FLAG_MAXPOWER", 23, nil, 32) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING", "MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING", 23, nil, 64) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT", "MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT", 23, nil, 128) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING", "MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING", 23, nil, 256) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT", "MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT", 23, nil, 512) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT", "MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT", 23, nil, 1024) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT", "MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT", 23, nil, 2048) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING", "MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING", 23, nil, 4096) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING", "MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING", 23, nil, 8192) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT", "MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT", 23, nil, 16384) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT", "MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT", 23, nil, 32768) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT", "MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT", 23, nil, 65536) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT", "MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT", 23, nil, 131072) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT", "MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT", 23, nil, 262144) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_START_INHIBITED = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_START_INHIBITED", "MAV_GENERATOR_STATUS_FLAG_START_INHIBITED", 23, nil, 524288) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED", "MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED", 23, nil, 1048576) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_WARMING_UP = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_WARMING_UP", "MAV_GENERATOR_STATUS_FLAG_WARMING_UP", 23, nil, 2097152) +f.GENERATOR_STATUS_status_flagMAV_GENERATOR_STATUS_FLAG_IDLE = ProtoField.bool("mavlink_proto.GENERATOR_STATUS_status.MAV_GENERATOR_STATUS_FLAG_IDLE", "MAV_GENERATOR_STATUS_FLAG_IDLE", 23, nil, 4194304) f.GENERATOR_STATUS_generator_speed = ProtoField.new("generator_speed (uint16_t)", "mavlink_proto.GENERATOR_STATUS_generator_speed", ftypes.UINT16, nil) f.GENERATOR_STATUS_battery_current = ProtoField.new("battery_current (float)", "mavlink_proto.GENERATOR_STATUS_battery_current", ftypes.FLOAT, nil) f.GENERATOR_STATUS_load_current = ProtoField.new("load_current (float)", "mavlink_proto.GENERATOR_STATUS_load_current", ftypes.FLOAT, nil) @@ -9823,10 +9928,10 @@ f.WINCH_STATUS_voltage = ProtoField.new("voltage (float)", "mavlink_proto.WINCH_ f.WINCH_STATUS_current = ProtoField.new("current (float)", "mavlink_proto.WINCH_STATUS_current", ftypes.FLOAT, nil) f.WINCH_STATUS_temperature = ProtoField.new("temperature (int16_t)", "mavlink_proto.WINCH_STATUS_temperature", ftypes.INT16, nil) f.WINCH_STATUS_status = ProtoField.new("status (MAV_WINCH_STATUS_FLAG)", "mavlink_proto.WINCH_STATUS_status", ftypes.UINT32, nil) -f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_HEALTHY = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_HEALTHY", "MAV_WINCH_STATUS_HEALTHY") -f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_FULLY_RETRACTED = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_FULLY_RETRACTED", "MAV_WINCH_STATUS_FULLY_RETRACTED") -f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_MOVING = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_MOVING", "MAV_WINCH_STATUS_MOVING") -f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_CLUTCH_ENGAGED = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_CLUTCH_ENGAGED", "MAV_WINCH_STATUS_CLUTCH_ENGAGED") +f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_HEALTHY = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_HEALTHY", "MAV_WINCH_STATUS_HEALTHY", 4, nil, 1) +f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_FULLY_RETRACTED = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_FULLY_RETRACTED", "MAV_WINCH_STATUS_FULLY_RETRACTED", 4, nil, 2) +f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_MOVING = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_MOVING", "MAV_WINCH_STATUS_MOVING", 4, nil, 4) +f.WINCH_STATUS_status_flagMAV_WINCH_STATUS_CLUTCH_ENGAGED = ProtoField.bool("mavlink_proto.WINCH_STATUS_status.MAV_WINCH_STATUS_CLUTCH_ENGAGED", "MAV_WINCH_STATUS_CLUTCH_ENGAGED", 4, nil, 8) f.OPEN_DRONE_ID_BASIC_ID_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.OPEN_DRONE_ID_BASIC_ID_target_system", ftypes.UINT8, nil) f.OPEN_DRONE_ID_BASIC_ID_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.OPEN_DRONE_ID_BASIC_ID_target_component", ftypes.UINT8, nil) @@ -10319,7 +10424,9 @@ f.UAVIONIX_ADSB_OUT_CFG_aircraftSize = ProtoField.new("aircraftSize (UAVIONIX_AD f.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLat = ProtoField.new("gpsOffsetLat (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLat", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) f.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLon = ProtoField.new("gpsOffsetLon (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLon", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) f.UAVIONIX_ADSB_OUT_CFG_stallSpeed = ProtoField.new("stallSpeed (uint16_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_stallSpeed", ftypes.UINT16, nil) -f.UAVIONIX_ADSB_OUT_CFG_rfSelect = ProtoField.new("rfSelect (UAVIONIX_ADSB_OUT_RF_SELECT)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_rfSelect", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_OUT_RF_SELECT) +f.UAVIONIX_ADSB_OUT_CFG_rfSelect = ProtoField.new("rfSelect (UAVIONIX_ADSB_OUT_RF_SELECT)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_rfSelect", ftypes.UINT8, nil) +f.UAVIONIX_ADSB_OUT_CFG_rfSelect_flagUAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CFG_rfSelect.UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED", "UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED", 2, nil, 1) +f.UAVIONIX_ADSB_OUT_CFG_rfSelect_flagUAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CFG_rfSelect.UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED", "UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED", 2, nil, 2) f.UAVIONIX_ADSB_OUT_DYNAMIC_utcTime = ProtoField.new("utcTime (uint32_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_utcTime", ftypes.UINT32, nil) f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsLat = ProtoField.new("gpsLat (int32_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_gpsLat", ftypes.INT32, nil) @@ -10336,14 +10443,17 @@ f.UAVIONIX_ADSB_OUT_DYNAMIC_velNS = ProtoField.new("velNS (int16_t)", "mavlink_p f.UAVIONIX_ADSB_OUT_DYNAMIC_VelEW = ProtoField.new("VelEW (int16_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_VelEW", ftypes.INT16, nil) f.UAVIONIX_ADSB_OUT_DYNAMIC_emergencyStatus = ProtoField.new("emergencyStatus (UAVIONIX_ADSB_EMERGENCY_STATUS)", "mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_emergencyStatus", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_EMERGENCY_STATUS) f.UAVIONIX_ADSB_OUT_DYNAMIC_state = ProtoField.new("state (UAVIONIX_ADSB_OUT_DYNAMIC_STATE)", "mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state", ftypes.UINT16, nil) -f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE") -f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED") -f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED") -f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND") -f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT") +f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", 5, nil, 1) +f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", 5, nil, 2) +f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED", 5, nil, 4) +f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND", 5, nil, 8) +f.UAVIONIX_ADSB_OUT_DYNAMIC_state_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_state.UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT", "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT", 5, nil, 16) f.UAVIONIX_ADSB_OUT_DYNAMIC_squawk = ProtoField.new("squawk (uint16_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_DYNAMIC_squawk", ftypes.UINT16, nil) -f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth = ProtoField.new("rfHealth (UAVIONIX_ADSB_RF_HEALTH)", "mavlink_proto.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_RF_HEALTH) +f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth = ProtoField.new("rfHealth (UAVIONIX_ADSB_RF_HEALTH)", "mavlink_proto.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth", ftypes.UINT8, nil) +f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth_flagUAVIONIX_ADSB_RF_HEALTH_OK = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth.UAVIONIX_ADSB_RF_HEALTH_OK", "UAVIONIX_ADSB_RF_HEALTH_OK", 5, nil, 1) +f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth_flagUAVIONIX_ADSB_RF_HEALTH_FAIL_TX = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth.UAVIONIX_ADSB_RF_HEALTH_FAIL_TX", "UAVIONIX_ADSB_RF_HEALTH_FAIL_TX", 5, nil, 2) +f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth_flagUAVIONIX_ADSB_RF_HEALTH_FAIL_RX = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth.UAVIONIX_ADSB_RF_HEALTH_FAIL_RX", "UAVIONIX_ADSB_RF_HEALTH_FAIL_RX", 5, nil, 16) f.UAVIONIX_ADSB_OUT_CFG_REGISTRATION_registration = ProtoField.new("registration (char)", "mavlink_proto.UAVIONIX_ADSB_OUT_CFG_REGISTRATION_registration", ftypes.STRING, nil) @@ -10352,37 +10462,38 @@ f.UAVIONIX_ADSB_OUT_CFG_FLIGHTID_flight_id = ProtoField.new("flight_id (char)", f.UAVIONIX_ADSB_GET_ReqMessageId = ProtoField.new("ReqMessageId (uint32_t)", "mavlink_proto.UAVIONIX_ADSB_GET_ReqMessageId", ftypes.UINT32, nil) f.UAVIONIX_ADSB_OUT_CONTROL_state = ProtoField.new("state (UAVIONIX_ADSB_OUT_CONTROL_STATE)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state", ftypes.UINT8, nil) -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED") -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND", "UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND") -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE", "UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE") -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED") -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED") -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED") -f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED") +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED", 8, nil, 1) +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND", "UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND", 8, nil, 4) +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE", "UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE", 8, nil, 8) +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED", 8, nil, 16) +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED", 8, nil, 32) +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED", 8, nil, 64) +f.UAVIONIX_ADSB_OUT_CONTROL_state_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_state.UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED", "UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED", 8, nil, 128) f.UAVIONIX_ADSB_OUT_CONTROL_baroAltMSL = ProtoField.new("baroAltMSL (int32_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_baroAltMSL", ftypes.INT32, nil) f.UAVIONIX_ADSB_OUT_CONTROL_squawk = ProtoField.new("squawk (uint16_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_squawk", ftypes.UINT16, nil) f.UAVIONIX_ADSB_OUT_CONTROL_emergencyStatus = ProtoField.new("emergencyStatus (UAVIONIX_ADSB_EMERGENCY_STATUS)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_emergencyStatus", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_EMERGENCY_STATUS) f.UAVIONIX_ADSB_OUT_CONTROL_flight_id = ProtoField.new("flight_id (char)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_flight_id", ftypes.STRING, nil) -f.UAVIONIX_ADSB_OUT_CONTROL_x_bit = ProtoField.new("x_bit (UAVIONIX_ADSB_XBIT)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_x_bit", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_XBIT) +f.UAVIONIX_ADSB_OUT_CONTROL_x_bit = ProtoField.new("x_bit (UAVIONIX_ADSB_XBIT)", "mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_x_bit", ftypes.UINT8, nil) +f.UAVIONIX_ADSB_OUT_CONTROL_x_bit_flagUAVIONIX_ADSB_XBIT_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_CONTROL_x_bit.UAVIONIX_ADSB_XBIT_ENABLED", "UAVIONIX_ADSB_XBIT_ENABLED", 8, nil, 128) f.UAVIONIX_ADSB_OUT_STATUS_state = ProtoField.new("state (UAVIONIX_ADSB_OUT_STATUS_STATE)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state", ftypes.UINT8, nil) -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND", "UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST", "UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE", "UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED") -f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED") +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND", "UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND", 8, nil, 1) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST", "UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST", 8, nil, 2) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED", 8, nil, 4) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE", "UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE", 8, nil, 8) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED", 8, nil, 16) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED", 8, nil, 32) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED", 8, nil, 64) +f.UAVIONIX_ADSB_OUT_STATUS_state_flagUAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_state.UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED", "UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED", 8, nil, 128) f.UAVIONIX_ADSB_OUT_STATUS_squawk = ProtoField.new("squawk (uint16_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_squawk", ftypes.UINT16, nil) f.UAVIONIX_ADSB_OUT_STATUS_NIC_NACp = ProtoField.new("NIC_NACp (UAVIONIX_ADSB_OUT_STATUS_NIC_NACP)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_NIC_NACp", ftypes.UINT8, enumEntryName.UAVIONIX_ADSB_OUT_STATUS_NIC_NACP) f.UAVIONIX_ADSB_OUT_STATUS_boardTemp = ProtoField.new("boardTemp (uint8_t)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_boardTemp", ftypes.UINT8, nil) f.UAVIONIX_ADSB_OUT_STATUS_fault = ProtoField.new("fault (UAVIONIX_ADSB_OUT_STATUS_FAULT)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault", ftypes.UINT8, nil) -f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL", "UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL") -f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS", "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS") -f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL", "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL") -f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL", "UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL") -f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", "UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ") +f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL", "UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL", 8, nil, 8) +f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS", "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS", 8, nil, 16) +f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL", "UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL", 8, nil, 32) +f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL", "UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL", 8, nil, 64) +f.UAVIONIX_ADSB_OUT_STATUS_fault_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ = ProtoField.bool("mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_fault.UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", "UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ", 8, nil, 128) f.UAVIONIX_ADSB_OUT_STATUS_flight_id = ProtoField.new("flight_id (char)", "mavlink_proto.UAVIONIX_ADSB_OUT_STATUS_flight_id", ftypes.STRING, nil) f.ICAROUS_HEARTBEAT_status = ProtoField.new("status (ICAROUS_FMS_STATE)", "mavlink_proto.ICAROUS_HEARTBEAT_status", ftypes.UINT8, enumEntryName.ICAROUS_FMS_STATE) @@ -10490,723 +10601,451 @@ f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset = ProtoField.new("offset (uint32_t)", "m f.HEARTBEAT_type = ProtoField.new("type (MAV_TYPE)", "mavlink_proto.HEARTBEAT_type", ftypes.UINT8, enumEntryName.MAV_TYPE) f.HEARTBEAT_autopilot = ProtoField.new("autopilot (MAV_AUTOPILOT)", "mavlink_proto.HEARTBEAT_autopilot", ftypes.UINT8, enumEntryName.MAV_AUTOPILOT) f.HEARTBEAT_base_mode = ProtoField.new("base_mode (MAV_MODE_FLAG)", "mavlink_proto.HEARTBEAT_base_mode", ftypes.UINT8, nil) -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED") -f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED") +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", "MAV_MODE_FLAG_CUSTOM_MODE_ENABLED", 8, nil, 1) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_TEST_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_TEST_ENABLED", "MAV_MODE_FLAG_TEST_ENABLED", 8, nil, 2) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_AUTO_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_AUTO_ENABLED", "MAV_MODE_FLAG_AUTO_ENABLED", 8, nil, 4) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_GUIDED_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_GUIDED_ENABLED", "MAV_MODE_FLAG_GUIDED_ENABLED", 8, nil, 8) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_STABILIZE_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_STABILIZE_ENABLED", "MAV_MODE_FLAG_STABILIZE_ENABLED", 8, nil, 16) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_HIL_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_HIL_ENABLED", "MAV_MODE_FLAG_HIL_ENABLED", 8, nil, 32) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", "MAV_MODE_FLAG_MANUAL_INPUT_ENABLED", 8, nil, 64) +f.HEARTBEAT_base_mode_flagMAV_MODE_FLAG_SAFETY_ARMED = ProtoField.bool("mavlink_proto.HEARTBEAT_base_mode.MAV_MODE_FLAG_SAFETY_ARMED", "MAV_MODE_FLAG_SAFETY_ARMED", 8, nil, 128) f.HEARTBEAT_custom_mode = ProtoField.new("custom_mode (uint32_t)", "mavlink_proto.HEARTBEAT_custom_mode", ftypes.UINT32, nil) f.HEARTBEAT_system_status = ProtoField.new("system_status (MAV_STATE)", "mavlink_proto.HEARTBEAT_system_status", ftypes.UINT8, enumEntryName.MAV_STATE) f.HEARTBEAT_mavlink_version = ProtoField.new("mavlink_version (uint8_t)", "mavlink_proto.HEARTBEAT_mavlink_version", ftypes.UINT8, nil) -- dissect flag field -function dissect_flags_LIMIT_MODULE(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagLIMIT_GPSLOCK"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " LIMIT_GPSLOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagLIMIT_GEOFENCE"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". LIMIT_GEOFENCE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagLIMIT_ALTITUDE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. LIMIT_ALTITUDE: " .. tostring(bitval ~= 0)) +function dissect_flags_LIMIT_MODULE(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagLIMIT_GPSLOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagLIMIT_GEOFENCE"], tvbrange, value) + tree:add_le(f[name .. "_flagLIMIT_ALTITUDE"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_RALLY_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagFAVORABLE_WIND"], tvbrange, value) + tree:add_le(f[name .. "_flagLAND_IMMEDIATELY"], tvbrange, value) end -- dissect flag field -function dissect_flags_RALLY_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagFAVORABLE_WIND"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " FAVORABLE_WIND: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagLAND_IMMEDIATELY"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". LAND_IMMEDIATELY: " .. tostring(bitval ~= 0)) +function dissect_flags_GOPRO_HEARTBEAT_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGOPRO_FLAG_RECORDING"], tvbrange, value) + tree:add_le(f[name .. "_flagGOPRO_HEARTBEAT_FLAGS_ENUM_END"], tvbrange, value) end -- dissect flag field -function dissect_flags_GOPRO_HEARTBEAT_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGOPRO_FLAG_RECORDING"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " GOPRO_FLAG_RECORDING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGOPRO_HEARTBEAT_FLAGS_ENUM_END"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". GOPRO_HEARTBEAT_FLAGS_ENUM_END: " .. tostring(bitval ~= 0)) +function dissect_flags_GOPRO_VIDEO_SETTINGS_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGOPRO_VIDEO_SETTINGS_TV_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagGOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END"], tvbrange, value) end -- dissect flag field -function dissect_flags_GOPRO_VIDEO_SETTINGS_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGOPRO_VIDEO_SETTINGS_TV_MODE"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " GOPRO_VIDEO_SETTINGS_TV_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". GOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END: " .. tostring(bitval ~= 0)) +function dissect_flags_EKF_STATUS_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagEKF_ATTITUDE"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_VELOCITY_HORIZ"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_VELOCITY_VERT"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_POS_HORIZ_REL"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_POS_HORIZ_ABS"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_POS_VERT_ABS"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_POS_VERT_AGL"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_CONST_POS_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_PRED_POS_HORIZ_REL"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_PRED_POS_HORIZ_ABS"], tvbrange, value) + tree:add_le(f[name .. "_flagEKF_UNINITIALIZED"], tvbrange, value) end -- dissect flag field -function dissect_flags_EKF_STATUS_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagEKF_ATTITUDE"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " EKF_ATTITUDE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagEKF_VELOCITY_HORIZ"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". EKF_VELOCITY_HORIZ: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagEKF_VELOCITY_VERT"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. EKF_VELOCITY_VERT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagEKF_POS_HORIZ_REL"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... EKF_POS_HORIZ_REL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagEKF_POS_HORIZ_ABS"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... EKF_POS_HORIZ_ABS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagEKF_POS_VERT_ABS"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... EKF_POS_VERT_ABS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagEKF_POS_VERT_AGL"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... EKF_POS_VERT_AGL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagEKF_CONST_POS_MODE"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... EKF_CONST_POS_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagEKF_PRED_POS_HORIZ_REL"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... EKF_PRED_POS_HORIZ_REL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagEKF_PRED_POS_HORIZ_ABS"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... EKF_PRED_POS_HORIZ_ABS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagEKF_UNINITIALIZED"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... EKF_UNINITIALIZED: " .. tostring(bitval ~= 0)) +function dissect_flags_HL_FAILURE_FLAG(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_GPS"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_ABSOLUTE_PRESSURE"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_3D_ACCEL"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_3D_GYRO"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_3D_MAG"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_TERRAIN"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_BATTERY"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_RC_RECEIVER"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_OFFBOARD_LINK"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_ENGINE"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_GEOFENCE"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_ESTIMATOR"], tvbrange, value) + tree:add_le(f[name .. "_flagHL_FAILURE_FLAG_MISSION"], tvbrange, value) end -- dissect flag field -function dissect_flags_HL_FAILURE_FLAG(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_GPS"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " HL_FAILURE_FLAG_GPS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_ABSOLUTE_PRESSURE"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. HL_FAILURE_FLAG_ABSOLUTE_PRESSURE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_3D_ACCEL"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... HL_FAILURE_FLAG_3D_ACCEL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_3D_GYRO"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... HL_FAILURE_FLAG_3D_GYRO: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_3D_MAG"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... HL_FAILURE_FLAG_3D_MAG: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_TERRAIN"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... HL_FAILURE_FLAG_TERRAIN: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_BATTERY"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... HL_FAILURE_FLAG_BATTERY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_RC_RECEIVER"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... HL_FAILURE_FLAG_RC_RECEIVER: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_OFFBOARD_LINK"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... HL_FAILURE_FLAG_OFFBOARD_LINK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_ENGINE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... HL_FAILURE_FLAG_ENGINE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_GEOFENCE"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... HL_FAILURE_FLAG_GEOFENCE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 12), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_ESTIMATOR"], bitval ~= 0, "..." .. tostring(bitval) .. " .... .... .... HL_FAILURE_FLAG_ESTIMATOR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 13), 1) - tree:add(f[name .. "_flagHL_FAILURE_FLAG_MISSION"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... .... .... HL_FAILURE_FLAG_MISSION: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_SYS_STATUS_SENSOR(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_GYRO"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_MAG"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_GPS"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_MAG2"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_GEOFENCE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_AHRS"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_TERRAIN"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_REVERSE_MOTOR"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_LOGGING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_BATTERY"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_PROXIMITY"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_SATCOM"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_PREARM_CHECK"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_SYS_STATUS_SENSOR_PROPULSION"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_SYS_STATUS_SENSOR(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_GYRO"], bitval ~= 0, ".... .... .... .... .... .... .... ..." .. tostring(bitval) .. " MAV_SYS_STATUS_SENSOR_3D_GYRO: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL"], bitval ~= 0, ".... .... .... .... .... .... .... .." .. tostring(bitval) .. ". MAV_SYS_STATUS_SENSOR_3D_ACCEL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_MAG"], bitval ~= 0, ".... .... .... .... .... .... .... ." .. tostring(bitval) .. ".. MAV_SYS_STATUS_SENSOR_3D_MAG: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE"], bitval ~= 0, ".... .... .... .... .... .... .... " .. tostring(bitval) .. "... MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE"], bitval ~= 0, ".... .... .... .... .... .... ..." .. tostring(bitval) .. " .... MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_GPS"], bitval ~= 0, ".... .... .... .... .... .... .." .. tostring(bitval) .. ". .... MAV_SYS_STATUS_SENSOR_GPS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_OPTICAL_FLOW"], bitval ~= 0, ".... .... .... .... .... .... ." .. tostring(bitval) .. ".. .... MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_VISION_POSITION"], bitval ~= 0, ".... .... .... .... .... .... " .. tostring(bitval) .. "... .... MAV_SYS_STATUS_SENSOR_VISION_POSITION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_LASER_POSITION"], bitval ~= 0, ".... .... .... .... .... ..." .. tostring(bitval) .. " .... .... MAV_SYS_STATUS_SENSOR_LASER_POSITION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH"], bitval ~= 0, ".... .... .... .... .... .." .. tostring(bitval) .. ". .... .... MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL"], bitval ~= 0, ".... .... .... .... .... ." .. tostring(bitval) .. ".. .... .... MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION"], bitval ~= 0, ".... .... .... .... .... " .. tostring(bitval) .. "... .... .... MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 12), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_YAW_POSITION"], bitval ~= 0, ".... .... .... .... ..." .. tostring(bitval) .. " .... .... .... MAV_SYS_STATUS_SENSOR_YAW_POSITION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 13), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL"], bitval ~= 0, ".... .... .... .... .." .. tostring(bitval) .. ". .... .... .... MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 14), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL"], bitval ~= 0, ".... .... .... .... ." .. tostring(bitval) .. ".. .... .... .... MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 15), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS"], bitval ~= 0, ".... .... .... .... " .. tostring(bitval) .. "... .... .... .... MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 16), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_RC_RECEIVER"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " .... .... .... .... MAV_SYS_STATUS_SENSOR_RC_RECEIVER: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 17), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_GYRO2"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". .... .... .... .... MAV_SYS_STATUS_SENSOR_3D_GYRO2: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 18), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_ACCEL2"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. .... .... .... .... MAV_SYS_STATUS_SENSOR_3D_ACCEL2: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 19), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_3D_MAG2"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... .... .... .... .... MAV_SYS_STATUS_SENSOR_3D_MAG2: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 20), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_GEOFENCE"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... .... .... .... .... MAV_SYS_STATUS_GEOFENCE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 21), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_AHRS"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... .... .... .... .... MAV_SYS_STATUS_AHRS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 22), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_TERRAIN"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... .... .... .... .... MAV_SYS_STATUS_TERRAIN: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 23), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_REVERSE_MOTOR"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... .... .... .... .... MAV_SYS_STATUS_REVERSE_MOTOR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 24), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_LOGGING"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... .... .... .... .... MAV_SYS_STATUS_LOGGING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 25), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_BATTERY"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... .... .... .... .... MAV_SYS_STATUS_SENSOR_BATTERY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 26), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_PROXIMITY"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... .... .... .... .... MAV_SYS_STATUS_SENSOR_PROXIMITY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 27), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_SATCOM"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... .... .... .... .... MAV_SYS_STATUS_SENSOR_SATCOM: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 28), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_PREARM_CHECK"], bitval ~= 0, "..." .. tostring(bitval) .. " .... .... .... .... .... .... .... MAV_SYS_STATUS_PREARM_CHECK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 29), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_OBSTACLE_AVOIDANCE"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... .... .... .... .... .... .... MAV_SYS_STATUS_OBSTACLE_AVOIDANCE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 30), 1) - tree:add(f[name .. "_flagMAV_SYS_STATUS_SENSOR_PROPULSION"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... .... .... .... .... .... .... MAV_SYS_STATUS_SENSOR_PROPULSION: " .. tostring(bitval ~= 0)) +function dissect_flags_GIMBAL_DEVICE_CAP_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW"], tvbrange, value) end -- dissect flag field -function dissect_flags_GIMBAL_DEVICE_CAP_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW: " .. tostring(bitval ~= 0)) +function dissect_flags_GIMBAL_MANAGER_CAP_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL"], tvbrange, value) end -- dissect flag field -function dissect_flags_GIMBAL_DEVICE_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_FLAGS_RETRACT"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " GIMBAL_DEVICE_FLAGS_RETRACT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_FLAGS_NEUTRAL"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". GIMBAL_DEVICE_FLAGS_NEUTRAL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. GIMBAL_DEVICE_FLAGS_ROLL_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK"], bitval ~= 0, ".... " .. tostring(bitval) .. "... GIMBAL_DEVICE_FLAGS_PITCH_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK"], bitval ~= 0, "..." .. tostring(bitval) .. " .... GIMBAL_DEVICE_FLAGS_YAW_LOCK: " .. tostring(bitval ~= 0)) +function dissect_flags_GIMBAL_DEVICE_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_RETRACT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_NEUTRAL"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_ROLL_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_PITCH_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_LOCK"], tvbrange, value) end -- dissect flag field -function dissect_flags_GIMBAL_MANAGER_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGIMBAL_MANAGER_FLAGS_RETRACT"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " GIMBAL_MANAGER_FLAGS_RETRACT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGIMBAL_MANAGER_FLAGS_NEUTRAL"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". GIMBAL_MANAGER_FLAGS_NEUTRAL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. GIMBAL_MANAGER_FLAGS_ROLL_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK"], bitval ~= 0, ".... " .. tostring(bitval) .. "... GIMBAL_MANAGER_FLAGS_PITCH_LOCK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK"], bitval ~= 0, "..." .. tostring(bitval) .. " .... GIMBAL_MANAGER_FLAGS_YAW_LOCK: " .. tostring(bitval ~= 0)) +function dissect_flags_GIMBAL_MANAGER_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_RETRACT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_NEUTRAL"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK"], tvbrange, value) end -- dissect flag field -function dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING: " .. tostring(bitval ~= 0)) +function dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_POWER_STATUS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_POWER_STATUS_BRICK_VALID"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " MAV_POWER_STATUS_BRICK_VALID: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_POWER_STATUS_SERVO_VALID"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". MAV_POWER_STATUS_SERVO_VALID: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_POWER_STATUS_USB_CONNECTED"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. MAV_POWER_STATUS_USB_CONNECTED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_POWER_STATUS_PERIPH_OVERCURRENT"], bitval ~= 0, ".... " .. tostring(bitval) .. "... MAV_POWER_STATUS_PERIPH_OVERCURRENT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT"], bitval ~= 0, "..." .. tostring(bitval) .. " .... MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_POWER_STATUS_CHANGED"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... MAV_POWER_STATUS_CHANGED: " .. tostring(bitval ~= 0)) +function dissect_flags_AUTOTUNE_AXIS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagAUTOTUNE_AXIS_ROLL"], tvbrange, value) + tree:add_le(f[name .. "_flagAUTOTUNE_AXIS_PITCH"], tvbrange, value) + tree:add_le(f[name .. "_flagAUTOTUNE_AXIS_YAW"], tvbrange, value) end -- dissect flag field -function dissect_flags_SERIAL_CONTROL_FLAG(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagSERIAL_CONTROL_FLAG_REPLY"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " SERIAL_CONTROL_FLAG_REPLY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagSERIAL_CONTROL_FLAG_RESPOND"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". SERIAL_CONTROL_FLAG_RESPOND: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagSERIAL_CONTROL_FLAG_EXCLUSIVE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. SERIAL_CONTROL_FLAG_EXCLUSIVE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagSERIAL_CONTROL_FLAG_BLOCKING"], bitval ~= 0, ".... " .. tostring(bitval) .. "... SERIAL_CONTROL_FLAG_BLOCKING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagSERIAL_CONTROL_FLAG_MULTI"], bitval ~= 0, "..." .. tostring(bitval) .. " .... SERIAL_CONTROL_FLAG_MULTI: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_POWER_STATUS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_POWER_STATUS_BRICK_VALID"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_POWER_STATUS_SERVO_VALID"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_POWER_STATUS_USB_CONNECTED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_POWER_STATUS_PERIPH_OVERCURRENT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_POWER_STATUS_CHANGED"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_PROTOCOL_CAPABILITY(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_FLOAT"], bitval ~= 0, ".... .... .... .... .... ..." .. tostring(bitval) .. " MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_PARAM_FLOAT"], bitval ~= 0, ".... .... .... .... .... .." .. tostring(bitval) .. ". MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_INT"], bitval ~= 0, ".... .... .... .... .... ." .. tostring(bitval) .. ".. MAV_PROTOCOL_CAPABILITY_MISSION_INT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_COMMAND_INT"], bitval ~= 0, ".... .... .... .... .... " .. tostring(bitval) .. "... MAV_PROTOCOL_CAPABILITY_COMMAND_INT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_PARAM_UNION"], bitval ~= 0, ".... .... .... .... ..." .. tostring(bitval) .. " .... MAV_PROTOCOL_CAPABILITY_PARAM_UNION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_FTP"], bitval ~= 0, ".... .... .... .... .." .. tostring(bitval) .. ". .... MAV_PROTOCOL_CAPABILITY_FTP: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET"], bitval ~= 0, ".... .... .... .... ." .. tostring(bitval) .. ".. .... MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED"], bitval ~= 0, ".... .... .... .... " .. tostring(bitval) .. "... .... MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " .... .... MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_TERRAIN"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". .... .... MAV_PROTOCOL_CAPABILITY_TERRAIN: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. .... .... MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... .... .... MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 12), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... .... .... MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 13), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MAVLINK2"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... .... .... MAV_PROTOCOL_CAPABILITY_MAVLINK2: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 14), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_FENCE"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... .... .... MAV_PROTOCOL_CAPABILITY_MISSION_FENCE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 15), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_RALLY"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... .... .... MAV_PROTOCOL_CAPABILITY_MISSION_RALLY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 16), 1) - tree:add(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... .... .... MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION: " .. tostring(bitval ~= 0)) +function dissect_flags_SERIAL_CONTROL_FLAG(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagSERIAL_CONTROL_FLAG_REPLY"], tvbrange, value) + tree:add_le(f[name .. "_flagSERIAL_CONTROL_FLAG_RESPOND"], tvbrange, value) + tree:add_le(f[name .. "_flagSERIAL_CONTROL_FLAG_EXCLUSIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagSERIAL_CONTROL_FLAG_BLOCKING"], tvbrange, value) + tree:add_le(f[name .. "_flagSERIAL_CONTROL_FLAG_MULTI"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_BATTERY_FAULT(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_DEEP_DISCHARGE"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " MAV_BATTERY_FAULT_DEEP_DISCHARGE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_SPIKES"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". MAV_BATTERY_FAULT_SPIKES: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_CELL_FAIL"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. MAV_BATTERY_FAULT_CELL_FAIL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_OVER_CURRENT"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... MAV_BATTERY_FAULT_OVER_CURRENT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_OVER_TEMPERATURE"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... MAV_BATTERY_FAULT_OVER_TEMPERATURE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_UNDER_TEMPERATURE"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... MAV_BATTERY_FAULT_UNDER_TEMPERATURE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagMAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagBATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_PROTOCOL_CAPABILITY(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_FLOAT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_PARAM_FLOAT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_INT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_COMMAND_INT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_PARAM_UNION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_FTP"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_TERRAIN"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MAVLINK2"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_FENCE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_MISSION_RALLY"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_GENERATOR_STATUS_FLAG(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OFF"], bitval ~= 0, ".... .... .... .... .... ..." .. tostring(bitval) .. " MAV_GENERATOR_STATUS_FLAG_OFF: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_READY"], bitval ~= 0, ".... .... .... .... .... .." .. tostring(bitval) .. ". MAV_GENERATOR_STATUS_FLAG_READY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_GENERATING"], bitval ~= 0, ".... .... .... .... .... ." .. tostring(bitval) .. ".. MAV_GENERATOR_STATUS_FLAG_GENERATING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_CHARGING"], bitval ~= 0, ".... .... .... .... .... " .. tostring(bitval) .. "... MAV_GENERATOR_STATUS_FLAG_CHARGING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_REDUCED_POWER"], bitval ~= 0, ".... .... .... .... ..." .. tostring(bitval) .. " .... MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_MAXPOWER"], bitval ~= 0, ".... .... .... .... .." .. tostring(bitval) .. ". .... MAV_GENERATOR_STATUS_FLAG_MAXPOWER: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING"], bitval ~= 0, ".... .... .... .... ." .. tostring(bitval) .. ".. .... MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT"], bitval ~= 0, ".... .... .... .... " .. tostring(bitval) .. "... .... MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " .... .... MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". .... .... MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. .... .... MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... .... .... MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 12), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... .... .... MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 13), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_COOLING_WARNING"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... .... .... MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 14), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... .... .... MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 15), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... .... .... MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 16), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... .... .... MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 17), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... .... .... MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 18), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... .... .... MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 19), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_START_INHIBITED"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... .... .... MAV_GENERATOR_STATUS_FLAG_START_INHIBITED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 20), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED"], bitval ~= 0, "..." .. tostring(bitval) .. " .... .... .... .... .... MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 21), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_WARMING_UP"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... .... .... .... .... MAV_GENERATOR_STATUS_FLAG_WARMING_UP: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 22), 1) - tree:add(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_IDLE"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... .... .... .... .... MAV_GENERATOR_STATUS_FLAG_IDLE: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_BATTERY_FAULT(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_DEEP_DISCHARGE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_SPIKES"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_CELL_FAIL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_OVER_CURRENT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_OVER_TEMPERATURE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_UNDER_TEMPERATURE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE"], tvbrange, value) + tree:add_le(f[name .. "_flagBATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION"], tvbrange, value) end -- dissect flag field -function dissect_flags_ADSB_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VALID_COORDS"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " ADSB_FLAGS_VALID_COORDS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VALID_ALTITUDE"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". ADSB_FLAGS_VALID_ALTITUDE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VALID_HEADING"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. ADSB_FLAGS_VALID_HEADING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VALID_VELOCITY"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... ADSB_FLAGS_VALID_VELOCITY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VALID_CALLSIGN"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... ADSB_FLAGS_VALID_CALLSIGN: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VALID_SQUAWK"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... ADSB_FLAGS_VALID_SQUAWK: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagADSB_FLAGS_SIMULATED"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... ADSB_FLAGS_SIMULATED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagADSB_FLAGS_VERTICAL_VELOCITY_VALID"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... ADSB_FLAGS_VERTICAL_VELOCITY_VALID: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagADSB_FLAGS_BARO_VALID"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... ADSB_FLAGS_BARO_VALID: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 15), 1) - tree:add(f[name .. "_flagADSB_FLAGS_SOURCE_UAT"], bitval ~= 0, "" .. tostring(bitval) .. "... .... .... .... ADSB_FLAGS_SOURCE_UAT: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_GENERATOR_STATUS_FLAG(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OFF"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_READY"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_GENERATING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_CHARGING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_REDUCED_POWER"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_MAXPOWER"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_COOLING_WARNING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_START_INHIBITED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_WARMING_UP"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_GENERATOR_STATUS_FLAG_IDLE"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_DO_REPOSITION_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_DO_REPOSITION_FLAGS_CHANGE_MODE"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " MAV_DO_REPOSITION_FLAGS_CHANGE_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_DO_REPOSITION_FLAGS_ENUM_END"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". MAV_DO_REPOSITION_FLAGS_ENUM_END: " .. tostring(bitval ~= 0)) +function dissect_flags_ADSB_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VALID_COORDS"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VALID_ALTITUDE"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VALID_HEADING"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VALID_VELOCITY"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VALID_CALLSIGN"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VALID_SQUAWK"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_SIMULATED"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_VERTICAL_VELOCITY_VALID"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_BARO_VALID"], tvbrange, value) + tree:add_le(f[name .. "_flagADSB_FLAGS_SOURCE_UAT"], tvbrange, value) end -- dissect flag field -function dissect_flags_ESTIMATOR_STATUS_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagESTIMATOR_ATTITUDE"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " ESTIMATOR_ATTITUDE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagESTIMATOR_VELOCITY_HORIZ"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". ESTIMATOR_VELOCITY_HORIZ: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagESTIMATOR_VELOCITY_VERT"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. ESTIMATOR_VELOCITY_VERT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagESTIMATOR_POS_HORIZ_REL"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... ESTIMATOR_POS_HORIZ_REL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagESTIMATOR_POS_HORIZ_ABS"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... ESTIMATOR_POS_HORIZ_ABS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagESTIMATOR_POS_VERT_ABS"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... ESTIMATOR_POS_VERT_ABS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagESTIMATOR_POS_VERT_AGL"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... ESTIMATOR_POS_VERT_AGL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagESTIMATOR_CONST_POS_MODE"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... ESTIMATOR_CONST_POS_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagESTIMATOR_PRED_POS_HORIZ_REL"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... ESTIMATOR_PRED_POS_HORIZ_REL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagESTIMATOR_PRED_POS_HORIZ_ABS"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... ESTIMATOR_PRED_POS_HORIZ_ABS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagESTIMATOR_GPS_GLITCH"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... ESTIMATOR_GPS_GLITCH: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagESTIMATOR_ACCEL_ERROR"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... ESTIMATOR_ACCEL_ERROR: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_DO_REPOSITION_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_DO_REPOSITION_FLAGS_CHANGE_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_DO_REPOSITION_FLAGS_ENUM_END"], tvbrange, value) end -- dissect flag field -function dissect_flags_GPS_INPUT_IGNORE_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_ALT"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " GPS_INPUT_IGNORE_FLAG_ALT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_HDOP"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". GPS_INPUT_IGNORE_FLAG_HDOP: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VDOP"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. GPS_INPUT_IGNORE_FLAG_VDOP: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VEL_HORIZ"], bitval ~= 0, ".... " .. tostring(bitval) .. "... GPS_INPUT_IGNORE_FLAG_VEL_HORIZ: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VEL_VERT"], bitval ~= 0, "..." .. tostring(bitval) .. " .... GPS_INPUT_IGNORE_FLAG_VEL_VERT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY"], bitval ~= 0, "" .. tostring(bitval) .. "... .... GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY: " .. tostring(bitval ~= 0)) +function dissect_flags_ESTIMATOR_STATUS_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_ATTITUDE"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_VELOCITY_HORIZ"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_VELOCITY_VERT"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_POS_HORIZ_REL"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_POS_HORIZ_ABS"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_POS_VERT_ABS"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_POS_VERT_AGL"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_CONST_POS_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_PRED_POS_HORIZ_REL"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_PRED_POS_HORIZ_ABS"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_GPS_GLITCH"], tvbrange, value) + tree:add_le(f[name .. "_flagESTIMATOR_ACCEL_ERROR"], tvbrange, value) end -- dissect flag field -function dissect_flags_CAMERA_CAP_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_CAPTURE_VIDEO"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " CAMERA_CAP_FLAGS_CAPTURE_VIDEO: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_CAPTURE_IMAGE"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". CAMERA_CAP_FLAGS_CAPTURE_IMAGE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_MODES"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. CAMERA_CAP_FLAGS_HAS_MODES: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_BASIC_ZOOM"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_BASIC_FOCUS"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_VIDEO_STREAM"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_TRACKING_POINT"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... CAMERA_CAP_FLAGS_HAS_TRACKING_POINT: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS: " .. tostring(bitval ~= 0)) +function dissect_flags_GPS_INPUT_IGNORE_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_ALT"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_HDOP"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VDOP"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VEL_HORIZ"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VEL_VERT"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY"], tvbrange, value) end -- dissect flag field -function dissect_flags_VIDEO_STREAM_STATUS_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagVIDEO_STREAM_STATUS_FLAGS_RUNNING"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " VIDEO_STREAM_STATUS_FLAGS_RUNNING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagVIDEO_STREAM_STATUS_FLAGS_THERMAL"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". VIDEO_STREAM_STATUS_FLAGS_THERMAL: " .. tostring(bitval ~= 0)) +function dissect_flags_CAMERA_CAP_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_CAPTURE_VIDEO"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_CAPTURE_IMAGE"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_MODES"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_BASIC_ZOOM"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_BASIC_FOCUS"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_VIDEO_STREAM"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_TRACKING_POINT"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS"], tvbrange, value) end -- dissect flag field -function dissect_flags_POSITION_TARGET_TYPEMASK(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_X_IGNORE"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " POSITION_TARGET_TYPEMASK_X_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". POSITION_TARGET_TYPEMASK_Y_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. POSITION_TARGET_TYPEMASK_Z_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... POSITION_TARGET_TYPEMASK_VX_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... POSITION_TARGET_TYPEMASK_VY_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... POSITION_TARGET_TYPEMASK_VZ_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... POSITION_TARGET_TYPEMASK_AX_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... POSITION_TARGET_TYPEMASK_AY_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... POSITION_TARGET_TYPEMASK_AZ_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_FORCE_SET"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... POSITION_TARGET_TYPEMASK_FORCE_SET: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... POSITION_TARGET_TYPEMASK_YAW_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE: " .. tostring(bitval ~= 0)) +function dissect_flags_VIDEO_STREAM_STATUS_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagVIDEO_STREAM_STATUS_FLAGS_RUNNING"], tvbrange, value) + tree:add_le(f[name .. "_flagVIDEO_STREAM_STATUS_FLAGS_THERMAL"], tvbrange, value) end -- dissect flag field -function dissect_flags_ATTITUDE_TARGET_TYPEMASK(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE"], bitval ~= 0, "" .. tostring(bitval) .. "... .... ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE: " .. tostring(bitval ~= 0)) +function dissect_flags_CAMERA_TRACKING_TARGET_DATA(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_TRACKING_TARGET_DATA_EMBEDDED"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_TRACKING_TARGET_DATA_RENDERED"], tvbrange, value) + tree:add_le(f[name .. "_flagCAMERA_TRACKING_TARGET_DATA_IN_STATUS"], tvbrange, value) end -- dissect flag field -function dissect_flags_UTM_DATA_AVAIL_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_TIME_VALID"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " UTM_DATA_AVAIL_FLAGS_TIME_VALID: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE"], bitval ~= 0, ".... " .. tostring(bitval) .. "... UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE"], bitval ~= 0, "..." .. tostring(bitval) .. " .... UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE"], bitval ~= 0, "" .. tostring(bitval) .. "... .... UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE: " .. tostring(bitval ~= 0)) +function dissect_flags_POSITION_TARGET_TYPEMASK(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_X_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_Y_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_Z_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_VX_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_VY_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_VZ_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_AX_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_AY_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_AZ_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_FORCE_SET"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_YAW_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagPOSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE"], tvbrange, value) end -- dissect flag field -function dissect_flags_AIS_FLAGS(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagAIS_FLAGS_POSITION_ACCURACY"], bitval ~= 0, ".... .... .... ..." .. tostring(bitval) .. " AIS_FLAGS_POSITION_ACCURACY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagAIS_FLAGS_VALID_COG"], bitval ~= 0, ".... .... .... .." .. tostring(bitval) .. ". AIS_FLAGS_VALID_COG: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagAIS_FLAGS_VALID_VELOCITY"], bitval ~= 0, ".... .... .... ." .. tostring(bitval) .. ".. AIS_FLAGS_VALID_VELOCITY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagAIS_FLAGS_HIGH_VELOCITY"], bitval ~= 0, ".... .... .... " .. tostring(bitval) .. "... AIS_FLAGS_HIGH_VELOCITY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagAIS_FLAGS_VALID_TURN_RATE"], bitval ~= 0, ".... .... ..." .. tostring(bitval) .. " .... AIS_FLAGS_VALID_TURN_RATE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagAIS_FLAGS_TURN_RATE_SIGN_ONLY"], bitval ~= 0, ".... .... .." .. tostring(bitval) .. ". .... AIS_FLAGS_TURN_RATE_SIGN_ONLY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagAIS_FLAGS_VALID_DIMENSIONS"], bitval ~= 0, ".... .... ." .. tostring(bitval) .. ".. .... AIS_FLAGS_VALID_DIMENSIONS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagAIS_FLAGS_LARGE_BOW_DIMENSION"], bitval ~= 0, ".... .... " .. tostring(bitval) .. "... .... AIS_FLAGS_LARGE_BOW_DIMENSION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 8), 1) - tree:add(f[name .. "_flagAIS_FLAGS_LARGE_STERN_DIMENSION"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " .... .... AIS_FLAGS_LARGE_STERN_DIMENSION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 9), 1) - tree:add(f[name .. "_flagAIS_FLAGS_LARGE_PORT_DIMENSION"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". .... .... AIS_FLAGS_LARGE_PORT_DIMENSION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 10), 1) - tree:add(f[name .. "_flagAIS_FLAGS_LARGE_STARBOARD_DIMENSION"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. .... .... AIS_FLAGS_LARGE_STARBOARD_DIMENSION: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 11), 1) - tree:add(f[name .. "_flagAIS_FLAGS_VALID_CALLSIGN"], bitval ~= 0, ".... " .. tostring(bitval) .. "... .... .... AIS_FLAGS_VALID_CALLSIGN: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 12), 1) - tree:add(f[name .. "_flagAIS_FLAGS_VALID_NAME"], bitval ~= 0, "..." .. tostring(bitval) .. " .... .... .... AIS_FLAGS_VALID_NAME: " .. tostring(bitval ~= 0)) +function dissect_flags_ATTITUDE_TARGET_TYPEMASK(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE"], tvbrange, value) + tree:add_le(f[name .. "_flagATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_WINCH_STATUS_FLAG(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_WINCH_STATUS_HEALTHY"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " MAV_WINCH_STATUS_HEALTHY: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_WINCH_STATUS_FULLY_RETRACTED"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". MAV_WINCH_STATUS_FULLY_RETRACTED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_WINCH_STATUS_MOVING"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. MAV_WINCH_STATUS_MOVING: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_WINCH_STATUS_CLUTCH_ENGAGED"], bitval ~= 0, ".... " .. tostring(bitval) .. "... MAV_WINCH_STATUS_CLUTCH_ENGAGED: " .. tostring(bitval ~= 0)) +function dissect_flags_UTM_DATA_AVAIL_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_TIME_VALID"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE"], tvbrange, value) + tree:add_le(f[name .. "_flagUTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE"], tvbrange, value) end -- dissect flag field -function dissect_flags_UAVIONIX_ADSB_OUT_DYNAMIC_STATE(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND"], bitval ~= 0, ".... " .. tostring(bitval) .. "... UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT"], bitval ~= 0, "..." .. tostring(bitval) .. " .... UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT: " .. tostring(bitval ~= 0)) +function dissect_flags_AIS_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_POSITION_ACCURACY"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_VALID_COG"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_VALID_VELOCITY"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_HIGH_VELOCITY"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_VALID_TURN_RATE"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_TURN_RATE_SIGN_ONLY"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_VALID_DIMENSIONS"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_LARGE_BOW_DIMENSION"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_LARGE_STERN_DIMENSION"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_LARGE_PORT_DIMENSION"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_LARGE_STARBOARD_DIMENSION"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_VALID_CALLSIGN"], tvbrange, value) + tree:add_le(f[name .. "_flagAIS_FLAGS_VALID_NAME"], tvbrange, value) end -- dissect flag field -function dissect_flags_UAVIONIX_ADSB_OUT_CONTROL_STATE(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE"], bitval ~= 0, ".... " .. tostring(bitval) .. "... UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED"], bitval ~= 0, "..." .. tostring(bitval) .. " .... UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED"], bitval ~= 0, "" .. tostring(bitval) .. "... .... UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED: " .. tostring(bitval ~= 0)) +function dissect_flags_MAV_WINCH_STATUS_FLAG(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_WINCH_STATUS_HEALTHY"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_WINCH_STATUS_FULLY_RETRACTED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_WINCH_STATUS_MOVING"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_WINCH_STATUS_CLUTCH_ENGAGED"], tvbrange, value) end -- dissect flag field -function dissect_flags_UAVIONIX_ADSB_OUT_STATUS_STATE(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE"], bitval ~= 0, ".... " .. tostring(bitval) .. "... UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED"], bitval ~= 0, "..." .. tostring(bitval) .. " .... UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED"], bitval ~= 0, "" .. tostring(bitval) .. "... .... UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED: " .. tostring(bitval ~= 0)) +function dissect_flags_UAVIONIX_ADSB_OUT_DYNAMIC_STATE(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT"], tvbrange, value) end -- dissect flag field -function dissect_flags_UAVIONIX_ADSB_OUT_STATUS_FAULT(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL"], bitval ~= 0, ".... " .. tostring(bitval) .. "... UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS"], bitval ~= 0, "..." .. tostring(bitval) .. " .... UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ"], bitval ~= 0, "" .. tostring(bitval) .. "... .... UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ: " .. tostring(bitval ~= 0)) +function dissect_flags_UAVIONIX_ADSB_OUT_RF_SELECT(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_MODE_FLAG(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " MAV_MODE_FLAG_CUSTOM_MODE_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_TEST_ENABLED"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". MAV_MODE_FLAG_TEST_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_AUTO_ENABLED"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. MAV_MODE_FLAG_AUTO_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_GUIDED_ENABLED"], bitval ~= 0, ".... " .. tostring(bitval) .. "... MAV_MODE_FLAG_GUIDED_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_STABILIZE_ENABLED"], bitval ~= 0, "..." .. tostring(bitval) .. " .... MAV_MODE_FLAG_STABILIZE_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_HIL_ENABLED"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... MAV_MODE_FLAG_HIL_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... MAV_MODE_FLAG_MANUAL_INPUT_ENABLED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_SAFETY_ARMED"], bitval ~= 0, "" .. tostring(bitval) .. "... .... MAV_MODE_FLAG_SAFETY_ARMED: " .. tostring(bitval ~= 0)) +function dissect_flags_UAVIONIX_ADSB_RF_HEALTH(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_RF_HEALTH_OK"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_RF_HEALTH_FAIL_TX"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_RF_HEALTH_FAIL_RX"], tvbrange, value) end -- dissect flag field -function dissect_flags_MAV_MODE_FLAG_DECODE_POSITION(tree, name, value) - local bitval - bitval = bit.band(bit.rshift(value, 0), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE"], bitval ~= 0, ".... ..." .. tostring(bitval) .. " MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 1), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_TEST"], bitval ~= 0, ".... .." .. tostring(bitval) .. ". MAV_MODE_FLAG_DECODE_POSITION_TEST: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 2), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_AUTO"], bitval ~= 0, ".... ." .. tostring(bitval) .. ".. MAV_MODE_FLAG_DECODE_POSITION_AUTO: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 3), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_GUIDED"], bitval ~= 0, ".... " .. tostring(bitval) .. "... MAV_MODE_FLAG_DECODE_POSITION_GUIDED: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 4), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_STABILIZE"], bitval ~= 0, "..." .. tostring(bitval) .. " .... MAV_MODE_FLAG_DECODE_POSITION_STABILIZE: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 5), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_HIL"], bitval ~= 0, ".." .. tostring(bitval) .. ". .... MAV_MODE_FLAG_DECODE_POSITION_HIL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 6), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_MANUAL"], bitval ~= 0, "." .. tostring(bitval) .. ".. .... MAV_MODE_FLAG_DECODE_POSITION_MANUAL: " .. tostring(bitval ~= 0)) - bitval = bit.band(bit.rshift(value, 7), 1) - tree:add(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_SAFETY"], bitval ~= 0, "" .. tostring(bitval) .. "... .... MAV_MODE_FLAG_DECODE_POSITION_SAFETY: " .. tostring(bitval ~= 0)) +function dissect_flags_UAVIONIX_ADSB_OUT_CONTROL_STATE(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_UAVIONIX_ADSB_XBIT(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_XBIT_ENABLED"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_UAVIONIX_ADSB_OUT_STATUS_STATE(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_UAVIONIX_ADSB_OUT_STATUS_FAULT(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL"], tvbrange, value) + tree:add_le(f[name .. "_flagUAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_MODE_FLAG(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_CUSTOM_MODE_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_TEST_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_AUTO_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_GUIDED_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_STABILIZE_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_HIL_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_MANUAL_INPUT_ENABLED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_SAFETY_ARMED"], tvbrange, value) +end +-- dissect flag field +function dissect_flags_MAV_MODE_FLAG_DECODE_POSITION(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_TEST"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_AUTO"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_GUIDED"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_STABILIZE"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_HIL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_MANUAL"], tvbrange, value) + tree:add_le(f[name .. "_flagMAV_MODE_FLAG_DECODE_POSITION_SAFETY"], tvbrange, value) end -- dissect payload of message type SENSOR_OFFSETS function payload_fns.payload_150(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -11214,34 +11053,46 @@ function payload_fns.payload_150(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 36 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_mag_ofs_x, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_mag_ofs_y, padded(field_offset, 2)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_mag_ofs_z, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_mag_declination, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_raw_press, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_raw_temp, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_gyro_cal_x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_gyro_cal_y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_gyro_cal_z, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_accel_cal_x, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_accel_cal_y, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SENSOR_OFFSETS_accel_cal_z, padded(field_offset, 4)) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SENSOR_OFFSETS_mag_ofs_x, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SENSOR_OFFSETS_mag_ofs_y, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SENSOR_OFFSETS_mag_ofs_z, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_mag_declination, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SENSOR_OFFSETS_raw_press, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SENSOR_OFFSETS_raw_temp, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_gyro_cal_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_gyro_cal_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_gyro_cal_z, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_accel_cal_x, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_accel_cal_y, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SENSOR_OFFSETS_accel_cal_z, tvbrange, value) end -- dissect payload of message type SET_MAG_OFFSETS function payload_fns.payload_151(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -11249,20 +11100,25 @@ function payload_fns.payload_151(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 6 - subtree, value = tree:add_le(f.SET_MAG_OFFSETS_target_system, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.SET_MAG_OFFSETS_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_MAG_OFFSETS_mag_ofs_x, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.SET_MAG_OFFSETS_mag_ofs_y, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_MAG_OFFSETS_mag_ofs_z, padded(field_offset, 2)) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MAG_OFFSETS_target_system, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MAG_OFFSETS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_MAG_OFFSETS_mag_ofs_x, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_MAG_OFFSETS_mag_ofs_y, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_MAG_OFFSETS_mag_ofs_z, tvbrange, value) end -- dissect payload of message type MEMINFO function payload_fns.payload_152(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -11270,16 +11126,19 @@ function payload_fns.payload_152(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MEMINFO_brkval, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MEMINFO_freemem, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MEMINFO_freemem32, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MEMINFO_brkval, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MEMINFO_freemem, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MEMINFO_freemem32, tvbrange, value) end -- dissect payload of message type AP_ADC function payload_fns.payload_153(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 12 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 12) @@ -11287,22 +11146,28 @@ function payload_fns.payload_153(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AP_ADC_adc1, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.AP_ADC_adc2, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.AP_ADC_adc3, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.AP_ADC_adc4, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AP_ADC_adc5, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.AP_ADC_adc6, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AP_ADC_adc1, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AP_ADC_adc2, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AP_ADC_adc3, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AP_ADC_adc4, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AP_ADC_adc5, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AP_ADC_adc6, tvbrange, value) end -- dissect payload of message type DIGICAM_CONFIGURE function payload_fns.payload_154(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 15 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 15) @@ -11310,32 +11175,43 @@ function payload_fns.payload_154(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 6 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_target_system, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_target_component, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_mode, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_shutter_speed, padded(field_offset, 2)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_aperture, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_iso, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_exposure_type, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_command_id, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_engine_cut_off, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_extra_param, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DIGICAM_CONFIGURE_extra_value, padded(field_offset, 4)) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_target_system, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_target_component, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_mode, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_shutter_speed, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_aperture, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_iso, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_exposure_type, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_command_id, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_engine_cut_off, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_extra_param, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DIGICAM_CONFIGURE_extra_value, tvbrange, value) end -- dissect payload of message type DIGICAM_CONTROL function payload_fns.payload_155(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 13 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 13) @@ -11343,30 +11219,40 @@ function payload_fns.payload_155(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_target_component, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_session, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_zoom_pos, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_zoom_step, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_focus_lock, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_shot, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_command_id, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_extra_param, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DIGICAM_CONTROL_extra_value, padded(field_offset, 4)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_target_component, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_session, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_zoom_pos, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.DIGICAM_CONTROL_zoom_step, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_focus_lock, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_shot, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_command_id, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DIGICAM_CONTROL_extra_param, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DIGICAM_CONTROL_extra_value, tvbrange, value) end -- dissect payload of message type MOUNT_CONFIGURE function payload_fns.payload_156(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -11374,22 +11260,28 @@ function payload_fns.payload_156(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MOUNT_CONFIGURE_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.MOUNT_CONFIGURE_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MOUNT_CONFIGURE_mount_mode, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MOUNT_CONFIGURE_stab_roll, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MOUNT_CONFIGURE_stab_pitch, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.MOUNT_CONFIGURE_stab_yaw, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONFIGURE_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONFIGURE_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONFIGURE_mount_mode, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONFIGURE_stab_roll, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONFIGURE_stab_pitch, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONFIGURE_stab_yaw, tvbrange, value) end -- dissect payload of message type MOUNT_CONTROL function payload_fns.payload_157(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 15 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 15) @@ -11397,22 +11289,28 @@ function payload_fns.payload_157(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 12 - subtree, value = tree:add_le(f.MOUNT_CONTROL_target_system, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.MOUNT_CONTROL_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MOUNT_CONTROL_input_a, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MOUNT_CONTROL_input_b, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MOUNT_CONTROL_input_c, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.MOUNT_CONTROL_save_position, padded(field_offset, 1)) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONTROL_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MOUNT_CONTROL_input_a, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MOUNT_CONTROL_input_b, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MOUNT_CONTROL_input_c, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_CONTROL_save_position, tvbrange, value) end -- dissect payload of message type MOUNT_STATUS function payload_fns.payload_158(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 15 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 15) @@ -11420,22 +11318,28 @@ function payload_fns.payload_158(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 12 - subtree, value = tree:add_le(f.MOUNT_STATUS_target_system, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.MOUNT_STATUS_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MOUNT_STATUS_pointing_a, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MOUNT_STATUS_pointing_b, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MOUNT_STATUS_pointing_c, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.MOUNT_STATUS_mount_mode, padded(field_offset, 1)) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_STATUS_target_system, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_STATUS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MOUNT_STATUS_pointing_a, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MOUNT_STATUS_pointing_b, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MOUNT_STATUS_pointing_c, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_STATUS_mount_mode, tvbrange, value) end -- dissect payload of message type FENCE_POINT function payload_fns.payload_160(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 12 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 12) @@ -11443,22 +11347,28 @@ function payload_fns.payload_160(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.FENCE_POINT_target_system, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.FENCE_POINT_target_component, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.FENCE_POINT_idx, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.FENCE_POINT_count, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.FENCE_POINT_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.FENCE_POINT_lng, padded(field_offset, 4)) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_POINT_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_POINT_target_component, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_POINT_idx, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_POINT_count, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FENCE_POINT_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FENCE_POINT_lng, tvbrange, value) end -- dissect payload of message type FENCE_FETCH_POINT function payload_fns.payload_161(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -11466,16 +11376,19 @@ function payload_fns.payload_161(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.FENCE_FETCH_POINT_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.FENCE_FETCH_POINT_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.FENCE_FETCH_POINT_idx, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_FETCH_POINT_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_FETCH_POINT_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_FETCH_POINT_idx, tvbrange, value) end -- dissect payload of message type AHRS function payload_fns.payload_163(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -11483,24 +11396,31 @@ function payload_fns.payload_163(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AHRS_omegaIx, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.AHRS_omegaIy, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AHRS_omegaIz, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AHRS_accel_weight, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AHRS_renorm_val, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AHRS_error_rp, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.AHRS_error_yaw, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_omegaIx, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_omegaIy, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_omegaIz, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_accel_weight, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_renorm_val, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_error_rp, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS_error_yaw, tvbrange, value) end -- dissect payload of message type SIMSTATE function payload_fns.payload_164(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -11508,32 +11428,43 @@ function payload_fns.payload_164(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SIMSTATE_roll, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SIMSTATE_pitch, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SIMSTATE_yaw, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SIMSTATE_xacc, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SIMSTATE_yacc, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SIMSTATE_zacc, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SIMSTATE_xgyro, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SIMSTATE_ygyro, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SIMSTATE_zgyro, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SIMSTATE_lat, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SIMSTATE_lng, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_roll, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_pitch, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_yaw, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_xacc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_yacc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_zacc, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_xgyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_ygyro, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIMSTATE_zgyro, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SIMSTATE_lat, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SIMSTATE_lng, tvbrange, value) end -- dissect payload of message type HWSTATUS function payload_fns.payload_165(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -11541,14 +11472,16 @@ function payload_fns.payload_165(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HWSTATUS_Vcc, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.HWSTATUS_I2Cerr, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HWSTATUS_Vcc, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HWSTATUS_I2Cerr, tvbrange, value) end -- dissect payload of message type RADIO function payload_fns.payload_166(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -11556,24 +11489,31 @@ function payload_fns.payload_166(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.RADIO_rssi, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.RADIO_remrssi, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RADIO_txbuf, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.RADIO_noise, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RADIO_remnoise, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.RADIO_rxerrors, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.RADIO_fixed, padded(field_offset, 2)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_rssi, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_remrssi, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_txbuf, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_noise, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_remnoise, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_rxerrors, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_fixed, tvbrange, value) end -- dissect payload of message type LIMITS_STATUS function payload_fns.payload_167(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 22 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 22) @@ -11581,31 +11521,40 @@ function payload_fns.payload_167(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 18 - subtree, value = tree:add_le(f.LIMITS_STATUS_limits_state, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LIMITS_STATUS_last_trigger, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LIMITS_STATUS_last_action, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LIMITS_STATUS_last_recovery, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LIMITS_STATUS_last_clear, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LIMITS_STATUS_breach_count, padded(field_offset, 2)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.LIMITS_STATUS_mods_enabled, padded(field_offset, 1)) - dissect_flags_LIMIT_MODULE(subtree, "LIMITS_STATUS_mods_enabled", value) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LIMITS_STATUS_mods_required, padded(field_offset, 1)) - dissect_flags_LIMIT_MODULE(subtree, "LIMITS_STATUS_mods_required", value) - field_offset = offset + 21 - subtree, value = tree:add_le(f.LIMITS_STATUS_mods_triggered, padded(field_offset, 1)) - dissect_flags_LIMIT_MODULE(subtree, "LIMITS_STATUS_mods_triggered", value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_limits_state, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_last_trigger, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_last_action, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_last_recovery, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_last_clear, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_breach_count, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_mods_enabled, tvbrange, value) + dissect_flags_LIMIT_MODULE(subtree, "LIMITS_STATUS_mods_enabled", tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_mods_required, tvbrange, value) + dissect_flags_LIMIT_MODULE(subtree, "LIMITS_STATUS_mods_required", tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LIMITS_STATUS_mods_triggered, tvbrange, value) + dissect_flags_LIMIT_MODULE(subtree, "LIMITS_STATUS_mods_triggered", tvbrange, value) end -- dissect payload of message type WIND function payload_fns.payload_168(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 12 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 12) @@ -11613,16 +11562,19 @@ function payload_fns.payload_168(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.WIND_direction, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.WIND_speed, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.WIND_speed_z, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_direction, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_speed, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_speed_z, tvbrange, value) end -- dissect payload of message type DATA16 function payload_fns.payload_169(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 18 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 18) @@ -11630,46 +11582,64 @@ function payload_fns.payload_169(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DATA16_type, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.DATA16_len, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.DATA16_data_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.DATA16_data_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DATA16_data_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DATA16_data_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DATA16_data_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DATA16_data_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DATA16_data_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DATA16_data_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DATA16_data_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DATA16_data_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DATA16_data_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DATA16_data_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DATA16_data_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.DATA16_data_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DATA16_data_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.DATA16_data_15, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_type, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_len, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA16_data_15, tvbrange, value) end -- dissect payload of message type DATA32 function payload_fns.payload_170(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 34 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 34) @@ -11677,78 +11647,112 @@ function payload_fns.payload_170(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DATA32_type, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.DATA32_len, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.DATA32_data_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.DATA32_data_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DATA32_data_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DATA32_data_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DATA32_data_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DATA32_data_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DATA32_data_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DATA32_data_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DATA32_data_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DATA32_data_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DATA32_data_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DATA32_data_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DATA32_data_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.DATA32_data_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DATA32_data_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.DATA32_data_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.DATA32_data_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.DATA32_data_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.DATA32_data_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.DATA32_data_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.DATA32_data_20, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.DATA32_data_21, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.DATA32_data_22, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.DATA32_data_23, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.DATA32_data_24, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.DATA32_data_25, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.DATA32_data_26, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.DATA32_data_27, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.DATA32_data_28, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.DATA32_data_29, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.DATA32_data_30, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.DATA32_data_31, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_type, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_len, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_20, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_21, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_22, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_23, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_24, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_25, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_26, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_27, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_28, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_29, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_30, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA32_data_31, tvbrange, value) end -- dissect payload of message type DATA64 function payload_fns.payload_171(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 66 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 66) @@ -11756,142 +11760,208 @@ function payload_fns.payload_171(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DATA64_type, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.DATA64_len, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.DATA64_data_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.DATA64_data_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DATA64_data_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DATA64_data_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DATA64_data_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DATA64_data_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DATA64_data_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DATA64_data_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DATA64_data_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DATA64_data_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DATA64_data_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DATA64_data_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DATA64_data_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.DATA64_data_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DATA64_data_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.DATA64_data_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.DATA64_data_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.DATA64_data_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.DATA64_data_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.DATA64_data_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.DATA64_data_20, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.DATA64_data_21, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.DATA64_data_22, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.DATA64_data_23, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.DATA64_data_24, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.DATA64_data_25, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.DATA64_data_26, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.DATA64_data_27, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.DATA64_data_28, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.DATA64_data_29, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.DATA64_data_30, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.DATA64_data_31, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.DATA64_data_32, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.DATA64_data_33, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.DATA64_data_34, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.DATA64_data_35, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.DATA64_data_36, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.DATA64_data_37, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.DATA64_data_38, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.DATA64_data_39, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.DATA64_data_40, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.DATA64_data_41, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.DATA64_data_42, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.DATA64_data_43, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.DATA64_data_44, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.DATA64_data_45, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.DATA64_data_46, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.DATA64_data_47, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.DATA64_data_48, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.DATA64_data_49, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.DATA64_data_50, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.DATA64_data_51, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.DATA64_data_52, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.DATA64_data_53, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.DATA64_data_54, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.DATA64_data_55, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.DATA64_data_56, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.DATA64_data_57, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.DATA64_data_58, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.DATA64_data_59, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.DATA64_data_60, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.DATA64_data_61, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.DATA64_data_62, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.DATA64_data_63, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_type, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_len, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_20, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_21, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_22, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_23, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_24, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_25, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_26, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_27, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_28, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_29, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_30, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_31, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_32, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_33, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_34, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_35, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_36, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_37, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_38, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_39, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_40, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_41, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_42, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_43, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_44, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_45, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_46, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_47, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_48, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_49, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_50, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_51, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_52, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_53, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_54, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_55, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_56, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_57, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_58, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_59, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_60, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_61, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_62, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA64_data_63, tvbrange, value) end -- dissect payload of message type DATA96 function payload_fns.payload_172(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 98 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 98) @@ -11899,206 +11969,304 @@ function payload_fns.payload_172(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DATA96_type, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.DATA96_len, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.DATA96_data_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.DATA96_data_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DATA96_data_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DATA96_data_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DATA96_data_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DATA96_data_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DATA96_data_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DATA96_data_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DATA96_data_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DATA96_data_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DATA96_data_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DATA96_data_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DATA96_data_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.DATA96_data_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DATA96_data_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.DATA96_data_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.DATA96_data_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.DATA96_data_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.DATA96_data_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.DATA96_data_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.DATA96_data_20, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.DATA96_data_21, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.DATA96_data_22, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.DATA96_data_23, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.DATA96_data_24, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.DATA96_data_25, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.DATA96_data_26, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.DATA96_data_27, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.DATA96_data_28, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.DATA96_data_29, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.DATA96_data_30, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.DATA96_data_31, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.DATA96_data_32, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.DATA96_data_33, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.DATA96_data_34, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.DATA96_data_35, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.DATA96_data_36, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.DATA96_data_37, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.DATA96_data_38, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.DATA96_data_39, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.DATA96_data_40, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.DATA96_data_41, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.DATA96_data_42, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.DATA96_data_43, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.DATA96_data_44, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.DATA96_data_45, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.DATA96_data_46, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.DATA96_data_47, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.DATA96_data_48, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.DATA96_data_49, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.DATA96_data_50, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.DATA96_data_51, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.DATA96_data_52, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.DATA96_data_53, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.DATA96_data_54, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.DATA96_data_55, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.DATA96_data_56, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.DATA96_data_57, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.DATA96_data_58, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.DATA96_data_59, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.DATA96_data_60, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.DATA96_data_61, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.DATA96_data_62, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.DATA96_data_63, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.DATA96_data_64, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.DATA96_data_65, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.DATA96_data_66, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.DATA96_data_67, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.DATA96_data_68, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.DATA96_data_69, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.DATA96_data_70, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.DATA96_data_71, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.DATA96_data_72, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.DATA96_data_73, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.DATA96_data_74, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.DATA96_data_75, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.DATA96_data_76, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.DATA96_data_77, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.DATA96_data_78, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.DATA96_data_79, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.DATA96_data_80, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.DATA96_data_81, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.DATA96_data_82, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.DATA96_data_83, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.DATA96_data_84, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.DATA96_data_85, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.DATA96_data_86, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.DATA96_data_87, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.DATA96_data_88, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.DATA96_data_89, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.DATA96_data_90, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.DATA96_data_91, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.DATA96_data_92, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.DATA96_data_93, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.DATA96_data_94, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.DATA96_data_95, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_type, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_len, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_20, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_21, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_22, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_23, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_24, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_25, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_26, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_27, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_28, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_29, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_30, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_31, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_32, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_33, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_34, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_35, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_36, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_37, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_38, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_39, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_40, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_41, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_42, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_43, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_44, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_45, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_46, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_47, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_48, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_49, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_50, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_51, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_52, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_53, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_54, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_55, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_56, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_57, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_58, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_59, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_60, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_61, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_62, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_63, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_64, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_65, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_66, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_67, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_68, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_69, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_70, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_71, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_72, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_73, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_74, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_75, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_76, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_77, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_78, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_79, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_80, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_81, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_82, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_83, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_84, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_85, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_86, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_87, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_88, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_89, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_90, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_91, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_92, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_93, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_94, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA96_data_95, tvbrange, value) end -- dissect payload of message type RANGEFINDER function payload_fns.payload_173(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -12106,14 +12274,16 @@ function payload_fns.payload_173(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RANGEFINDER_distance, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RANGEFINDER_voltage, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.RANGEFINDER_distance, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.RANGEFINDER_voltage, tvbrange, value) end -- dissect payload of message type AIRSPEED_AUTOCAL function payload_fns.payload_174(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 48 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 48) @@ -12121,34 +12291,46 @@ function payload_fns.payload_174(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_vx, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_vy, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_vz, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_diff_pressure, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_EAS2TAS, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_ratio, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_state_x, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_state_y, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_state_z, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_Pax, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_Pby, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.AIRSPEED_AUTOCAL_Pcz, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_vx, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_vy, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_vz, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_diff_pressure, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_EAS2TAS, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_ratio, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_state_x, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_state_y, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_state_z, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_Pax, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_Pby, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AIRSPEED_AUTOCAL_Pcz, tvbrange, value) end -- dissect payload of message type RALLY_POINT function payload_fns.payload_175(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 19 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 19) @@ -12156,31 +12338,41 @@ function payload_fns.payload_175(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 14 - subtree, value = tree:add_le(f.RALLY_POINT_target_system, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.RALLY_POINT_target_component, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.RALLY_POINT_idx, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.RALLY_POINT_count, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.RALLY_POINT_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RALLY_POINT_lng, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RALLY_POINT_alt, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RALLY_POINT_break_alt, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RALLY_POINT_land_dir, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RALLY_POINT_flags, padded(field_offset, 1)) - dissect_flags_RALLY_FLAGS(subtree, "RALLY_POINT_flags", value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_POINT_target_system, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_POINT_target_component, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_POINT_idx, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_POINT_count, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.RALLY_POINT_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.RALLY_POINT_lng, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RALLY_POINT_alt, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RALLY_POINT_break_alt, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_POINT_land_dir, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_POINT_flags, tvbrange, value) + dissect_flags_RALLY_FLAGS(subtree, "RALLY_POINT_flags", tvbrange, value) end -- dissect payload of message type RALLY_FETCH_POINT function payload_fns.payload_176(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -12188,16 +12380,19 @@ function payload_fns.payload_176(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RALLY_FETCH_POINT_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.RALLY_FETCH_POINT_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.RALLY_FETCH_POINT_idx, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_FETCH_POINT_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_FETCH_POINT_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RALLY_FETCH_POINT_idx, tvbrange, value) end -- dissect payload of message type COMPASSMOT_STATUS function payload_fns.payload_177(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -12205,22 +12400,28 @@ function payload_fns.payload_177(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMPASSMOT_STATUS_throttle, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMPASSMOT_STATUS_current, padded(field_offset, 4)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.COMPASSMOT_STATUS_interference, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMPASSMOT_STATUS_CompensationX, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMPASSMOT_STATUS_CompensationY, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMPASSMOT_STATUS_CompensationZ, padded(field_offset, 4)) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMPASSMOT_STATUS_throttle, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMPASSMOT_STATUS_current, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMPASSMOT_STATUS_interference, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMPASSMOT_STATUS_CompensationX, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMPASSMOT_STATUS_CompensationY, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMPASSMOT_STATUS_CompensationZ, tvbrange, value) end -- dissect payload of message type AHRS2 function payload_fns.payload_178(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 24 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 24) @@ -12228,22 +12429,28 @@ function payload_fns.payload_178(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AHRS2_roll, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.AHRS2_pitch, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AHRS2_yaw, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AHRS2_altitude, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AHRS2_lat, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AHRS2_lng, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS2_roll, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS2_pitch, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS2_yaw, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS2_altitude, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AHRS2_lat, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AHRS2_lng, tvbrange, value) end -- dissect payload of message type CAMERA_STATUS function payload_fns.payload_179(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 29 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 29) @@ -12251,28 +12458,37 @@ function payload_fns.payload_179(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_STATUS_time_usec, padded(field_offset, 8)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.CAMERA_STATUS_target_system, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.CAMERA_STATUS_cam_idx, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_STATUS_img_idx, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_STATUS_event_id, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_STATUS_p1, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_STATUS_p2, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_STATUS_p3, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_STATUS_p4, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.CAMERA_STATUS_time_usec, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_STATUS_target_system, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_STATUS_cam_idx, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_STATUS_img_idx, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_STATUS_event_id, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_STATUS_p1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_STATUS_p2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_STATUS_p3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_STATUS_p4, tvbrange, value) end -- dissect payload of message type CAMERA_FEEDBACK function payload_fns.payload_180(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 47 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 47) @@ -12280,38 +12496,52 @@ function payload_fns.payload_180(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_time_usec, padded(field_offset, 8)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_target_system, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_cam_idx, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_img_idx, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_lng, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_alt_msl, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_alt_rel, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_roll, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_pitch, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_yaw, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_foc_len, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_flags, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.CAMERA_FEEDBACK_completed_captures, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.CAMERA_FEEDBACK_time_usec, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_FEEDBACK_target_system, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_FEEDBACK_cam_idx, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_FEEDBACK_img_idx, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FEEDBACK_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FEEDBACK_lng, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FEEDBACK_alt_msl, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FEEDBACK_alt_rel, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FEEDBACK_roll, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FEEDBACK_pitch, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FEEDBACK_yaw, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FEEDBACK_foc_len, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_FEEDBACK_flags, tvbrange, value) + tvbrange = padded(offset + 45, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_FEEDBACK_completed_captures, tvbrange, value) end -- dissect payload of message type BATTERY2 function payload_fns.payload_181(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 4 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 4) @@ -12319,14 +12549,16 @@ function payload_fns.payload_181(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.BATTERY2_voltage, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.BATTERY2_current_battery, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY2_voltage, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY2_current_battery, tvbrange, value) end -- dissect payload of message type AHRS3 function payload_fns.payload_182(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 40 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 40) @@ -12334,30 +12566,40 @@ function payload_fns.payload_182(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AHRS3_roll, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.AHRS3_pitch, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AHRS3_yaw, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AHRS3_altitude, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AHRS3_lat, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AHRS3_lng, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.AHRS3_v1, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.AHRS3_v2, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.AHRS3_v3, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.AHRS3_v4, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_roll, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_pitch, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_yaw, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_altitude, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AHRS3_lat, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AHRS3_lng, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_v1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_v2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_v3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AHRS3_v4, tvbrange, value) end -- dissect payload of message type AUTOPILOT_VERSION_REQUEST function payload_fns.payload_183(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -12365,14 +12607,16 @@ function payload_fns.payload_183(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_REQUEST_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_REQUEST_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_REQUEST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_REQUEST_target_component, tvbrange, value) end -- dissect payload of message type REMOTE_LOG_DATA_BLOCK function payload_fns.payload_184(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 206 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 206) @@ -12380,416 +12624,619 @@ function payload_fns.payload_184(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_seqno, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_0, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_1, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_2, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_3, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_4, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_5, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_6, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_7, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_8, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_9, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_10, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_11, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_12, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_13, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_14, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_15, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_16, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_17, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_18, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_19, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_20, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_21, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_22, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_23, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_24, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_25, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_26, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_27, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_28, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_29, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_30, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_31, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_32, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_33, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_34, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_35, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_36, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_37, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_38, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_39, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_40, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_41, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_42, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_43, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_44, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_45, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_46, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_47, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_48, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_49, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_50, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_51, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_52, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_53, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_54, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_55, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_56, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_57, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_58, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_59, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_60, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_61, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_62, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_63, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_64, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_65, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_66, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_67, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_68, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_69, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_70, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_71, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_72, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_73, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_74, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_75, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_76, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_77, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_78, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_79, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_80, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_81, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_82, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_83, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_84, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_85, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_86, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_87, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_88, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_89, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_90, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_91, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_92, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_93, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_94, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_95, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_96, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_97, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_98, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_99, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_100, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_101, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_102, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_103, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_104, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_105, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_106, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_107, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_108, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_109, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_110, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_111, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_112, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_113, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_114, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_115, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_116, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_117, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_118, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_119, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_120, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_121, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_122, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_123, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_124, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_125, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_126, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_127, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_128, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_129, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_130, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_131, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_132, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_133, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_134, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_135, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_136, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_137, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_138, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_139, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_140, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_141, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_142, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_143, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_144, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_145, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_146, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_147, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_148, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_149, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_150, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_151, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_152, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_153, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_154, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_155, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_156, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_157, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_158, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_159, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_160, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_161, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_162, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_163, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_164, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_165, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_166, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_167, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_168, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_169, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_170, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_171, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_172, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_173, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_174, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_175, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_176, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_177, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_178, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_179, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_180, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_181, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_182, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_183, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_184, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_185, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_186, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_187, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_188, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_189, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_190, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_191, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_192, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_193, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_194, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_195, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_196, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_197, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_198, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_199, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_seqno, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_0, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_1, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_2, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_3, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_4, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_5, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_6, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_7, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_8, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_9, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_10, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_11, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_12, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_13, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_14, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_15, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_16, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_17, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_18, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_19, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_20, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_21, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_22, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_23, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_24, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_25, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_26, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_27, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_28, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_29, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_30, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_31, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_32, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_33, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_34, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_35, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_36, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_37, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_38, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_39, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_40, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_41, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_42, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_43, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_44, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_45, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_46, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_47, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_48, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_49, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_50, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_51, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_52, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_53, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_54, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_55, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_56, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_57, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_58, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_59, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_60, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_61, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_62, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_63, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_64, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_65, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_66, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_67, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_68, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_69, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_70, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_71, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_72, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_73, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_74, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_75, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_76, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_77, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_78, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_79, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_80, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_81, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_82, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_83, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_84, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_85, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_86, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_87, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_88, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_89, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_90, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_91, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_92, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_93, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_94, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_95, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_96, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_97, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_98, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_99, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_100, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_101, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_102, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_103, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_104, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_105, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_106, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_107, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_108, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_109, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_110, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_111, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_112, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_113, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_114, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_115, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_116, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_117, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_118, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_119, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_120, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_121, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_122, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_123, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_124, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_125, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_126, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_127, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_128, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_129, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_130, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_131, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_132, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_133, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_134, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_135, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_136, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_137, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_138, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_139, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_140, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_141, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_142, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_143, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_144, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_145, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_146, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_147, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_148, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_149, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_150, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_151, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_152, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_153, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_154, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_155, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_156, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_157, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_158, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_159, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_160, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_161, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_162, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_163, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_164, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_165, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_166, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_167, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_168, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_169, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_170, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_171, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_172, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_173, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_174, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_175, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_176, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_177, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_178, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_179, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_180, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_181, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_182, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_183, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_184, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_185, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_186, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_187, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_188, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_189, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_190, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_191, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_192, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_193, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_194, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_195, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_196, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_197, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_198, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_DATA_BLOCK_data_199, tvbrange, value) end -- dissect payload of message type REMOTE_LOG_BLOCK_STATUS function payload_fns.payload_185(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 7 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 7) @@ -12797,18 +13244,22 @@ function payload_fns.payload_185(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_seqno, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_status, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_seqno, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REMOTE_LOG_BLOCK_STATUS_status, tvbrange, value) end -- dissect payload of message type LED_CONTROL function payload_fns.payload_186(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 29 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 29) @@ -12816,68 +13267,97 @@ function payload_fns.payload_186(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LED_CONTROL_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.LED_CONTROL_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.LED_CONTROL_instance, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.LED_CONTROL_pattern, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LED_CONTROL_custom_len, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_0, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_1, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_2, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_3, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_4, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_5, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_6, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_7, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_8, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_9, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_10, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_11, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_12, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_13, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_14, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_15, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_16, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_17, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_18, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_19, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_20, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_21, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_22, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LED_CONTROL_custom_bytes_23, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_instance, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_pattern, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_len, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_0, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_1, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_2, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_3, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_4, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_5, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_6, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_7, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_8, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_9, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_10, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_11, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_12, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_13, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_14, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_15, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_16, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_17, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_18, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_19, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_20, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_21, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_22, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LED_CONTROL_custom_bytes_23, tvbrange, value) end -- dissect payload of message type MAG_CAL_PROGRESS function payload_fns.payload_191(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 27 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 27) @@ -12885,46 +13365,64 @@ function payload_fns.payload_191(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 12 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_compass_id, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_cal_mask, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_cal_status, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_attempt, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_pct, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_0, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_1, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_2, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_3, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_4, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_5, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_6, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_7, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_8, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_9, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_direction_x, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_direction_y, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MAG_CAL_PROGRESS_direction_z, padded(field_offset, 4)) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_compass_id, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_cal_mask, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_cal_status, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_attempt, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_pct, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_0, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_1, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_2, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_3, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_4, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_5, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_6, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_7, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_8, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_completion_mask_9, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_direction_x, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_direction_y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_PROGRESS_direction_z, tvbrange, value) end -- dissect payload of message type EKF_STATUS_REPORT function payload_fns.payload_193(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 26 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 26) @@ -12932,25 +13430,32 @@ function payload_fns.payload_193(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 20 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_flags, padded(field_offset, 2)) - dissect_flags_EKF_STATUS_FLAGS(subtree, "EKF_STATUS_REPORT_flags", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_velocity_variance, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_pos_horiz_variance, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_pos_vert_variance, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_compass_variance, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_terrain_alt_variance, padded(field_offset, 4)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.EKF_STATUS_REPORT_airspeed_variance, padded(field_offset, 4)) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.EKF_STATUS_REPORT_flags, tvbrange, value) + dissect_flags_EKF_STATUS_FLAGS(subtree, "EKF_STATUS_REPORT_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_STATUS_REPORT_velocity_variance, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_STATUS_REPORT_pos_horiz_variance, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_STATUS_REPORT_pos_vert_variance, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_STATUS_REPORT_compass_variance, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_STATUS_REPORT_terrain_alt_variance, tvbrange, value) + tvbrange = padded(offset + 22, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EKF_STATUS_REPORT_airspeed_variance, tvbrange, value) end -- dissect payload of message type PID_TUNING function payload_fns.payload_194(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -12958,28 +13463,37 @@ function payload_fns.payload_194(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 24 - subtree, value = tree:add_le(f.PID_TUNING_axis, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PID_TUNING_desired, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.PID_TUNING_achieved, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.PID_TUNING_FF, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.PID_TUNING_P, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.PID_TUNING_I, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.PID_TUNING_D, padded(field_offset, 4)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.PID_TUNING_SRate, padded(field_offset, 4)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.PID_TUNING_PDmod, padded(field_offset, 4)) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PID_TUNING_axis, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_desired, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_achieved, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_FF, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_P, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_I, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_D, tvbrange, value) + tvbrange = padded(offset + 25, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_SRate, tvbrange, value) + tvbrange = padded(offset + 29, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PID_TUNING_PDmod, tvbrange, value) end -- dissect payload of message type DEEPSTALL function payload_fns.payload_195(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 37 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 37) @@ -12987,30 +13501,40 @@ function payload_fns.payload_195(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEEPSTALL_landing_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DEEPSTALL_landing_lon, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEEPSTALL_path_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DEEPSTALL_path_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DEEPSTALL_arc_entry_lat, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.DEEPSTALL_arc_entry_lon, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.DEEPSTALL_altitude, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.DEEPSTALL_expected_travel_distance, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.DEEPSTALL_cross_track_error, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.DEEPSTALL_stage, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.DEEPSTALL_landing_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.DEEPSTALL_landing_lon, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.DEEPSTALL_path_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.DEEPSTALL_path_lon, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.DEEPSTALL_arc_entry_lat, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.DEEPSTALL_arc_entry_lon, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEEPSTALL_altitude, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEEPSTALL_expected_travel_distance, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEEPSTALL_cross_track_error, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEEPSTALL_stage, tvbrange, value) end -- dissect payload of message type GIMBAL_REPORT function payload_fns.payload_200(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -13018,34 +13542,46 @@ function payload_fns.payload_200(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.GIMBAL_REPORT_target_system, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.GIMBAL_REPORT_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_time, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_angle_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_angle_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_angle_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_velocity_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_velocity_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GIMBAL_REPORT_delta_velocity_z, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GIMBAL_REPORT_joint_roll, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GIMBAL_REPORT_joint_el, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GIMBAL_REPORT_joint_az, padded(field_offset, 4)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_REPORT_target_system, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_REPORT_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_time, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_angle_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_angle_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_angle_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_velocity_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_velocity_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_delta_velocity_z, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_joint_roll, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_joint_el, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_REPORT_joint_az, tvbrange, value) end -- dissect payload of message type GIMBAL_CONTROL function payload_fns.payload_201(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 14 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 14) @@ -13053,20 +13589,25 @@ function payload_fns.payload_201(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 12 - subtree, value = tree:add_le(f.GIMBAL_CONTROL_target_system, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.GIMBAL_CONTROL_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_CONTROL_demanded_rate_x, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GIMBAL_CONTROL_demanded_rate_y, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GIMBAL_CONTROL_demanded_rate_z, padded(field_offset, 4)) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_CONTROL_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_CONTROL_demanded_rate_x, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_CONTROL_demanded_rate_y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_CONTROL_demanded_rate_z, tvbrange, value) end -- dissect payload of message type GIMBAL_TORQUE_CMD_REPORT function payload_fns.payload_214(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -13074,20 +13615,25 @@ function payload_fns.payload_214(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 6 - subtree, value = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_target_system, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_rl_torque_cmd, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_el_torque_cmd, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_az_torque_cmd, padded(field_offset, 2)) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_target_system, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_rl_torque_cmd, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_el_torque_cmd, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GIMBAL_TORQUE_CMD_REPORT_az_torque_cmd, tvbrange, value) end -- dissect payload of message type GOPRO_HEARTBEAT function payload_fns.payload_215(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -13095,17 +13641,20 @@ function payload_fns.payload_215(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GOPRO_HEARTBEAT_status, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GOPRO_HEARTBEAT_capture_mode, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GOPRO_HEARTBEAT_flags, padded(field_offset, 1)) - dissect_flags_GOPRO_HEARTBEAT_FLAGS(subtree, "GOPRO_HEARTBEAT_flags", value) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_HEARTBEAT_status, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_HEARTBEAT_capture_mode, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_HEARTBEAT_flags, tvbrange, value) + dissect_flags_GOPRO_HEARTBEAT_FLAGS(subtree, "GOPRO_HEARTBEAT_flags", tvbrange, value) end -- dissect payload of message type GOPRO_GET_REQUEST function payload_fns.payload_216(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -13113,16 +13662,19 @@ function payload_fns.payload_216(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GOPRO_GET_REQUEST_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GOPRO_GET_REQUEST_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GOPRO_GET_REQUEST_cmd_id, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_REQUEST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_REQUEST_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_REQUEST_cmd_id, tvbrange, value) end -- dissect payload of message type GOPRO_GET_RESPONSE function payload_fns.payload_217(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -13130,22 +13682,28 @@ function payload_fns.payload_217(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GOPRO_GET_RESPONSE_cmd_id, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GOPRO_GET_RESPONSE_status, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GOPRO_GET_RESPONSE_value_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.GOPRO_GET_RESPONSE_value_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GOPRO_GET_RESPONSE_value_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.GOPRO_GET_RESPONSE_value_3, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_RESPONSE_cmd_id, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_RESPONSE_status, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_RESPONSE_value_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_RESPONSE_value_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_RESPONSE_value_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_GET_RESPONSE_value_3, tvbrange, value) end -- dissect payload of message type GOPRO_SET_REQUEST function payload_fns.payload_218(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 7 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 7) @@ -13153,24 +13711,31 @@ function payload_fns.payload_218(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_cmd_id, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_value_0, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_value_1, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_value_2, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.GOPRO_SET_REQUEST_value_3, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_cmd_id, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_value_0, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_value_1, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_value_2, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_REQUEST_value_3, tvbrange, value) end -- dissect payload of message type GOPRO_SET_RESPONSE function payload_fns.payload_219(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -13178,14 +13743,16 @@ function payload_fns.payload_219(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GOPRO_SET_RESPONSE_cmd_id, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GOPRO_SET_RESPONSE_status, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_RESPONSE_cmd_id, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GOPRO_SET_RESPONSE_status, tvbrange, value) end -- dissect payload of message type RPM function payload_fns.payload_226(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -13193,14 +13760,16 @@ function payload_fns.payload_226(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RPM_rpm1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RPM_rpm2, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.RPM_rpm1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.RPM_rpm2, tvbrange, value) end -- dissect payload of message type DEVICE_OP_READ function payload_fns.payload_11000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 52 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 52) @@ -13208,30 +13777,40 @@ function payload_fns.payload_11000(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.DEVICE_OP_READ_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DEVICE_OP_READ_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEVICE_OP_READ_request_id, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DEVICE_OP_READ_bustype, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DEVICE_OP_READ_bus, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEVICE_OP_READ_address, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DEVICE_OP_READ_busname, padded(field_offset, 40)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.DEVICE_OP_READ_regstart, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.DEVICE_OP_READ_count, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.DEVICE_OP_READ_bank, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_request_id, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_bustype, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_bus, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_address, tvbrange, value) + tvbrange = padded(offset + 9, 40) + value = tvbrange:string() + subtree = tree:add_le(f.DEVICE_OP_READ_busname, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_regstart, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_count, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_bank, tvbrange, value) end -- dissect payload of message type DEVICE_OP_READ_REPLY function payload_fns.payload_11001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 136 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 136) @@ -13239,276 +13818,409 @@ function payload_fns.payload_11001(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_request_id, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_result, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_regstart, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_count, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_0, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_1, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_2, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_3, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_4, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_5, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_6, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_7, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_8, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_9, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_10, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_11, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_12, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_13, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_14, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_15, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_16, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_17, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_18, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_19, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_20, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_21, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_22, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_23, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_24, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_25, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_26, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_27, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_28, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_29, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_30, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_31, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_32, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_33, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_34, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_35, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_36, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_37, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_38, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_39, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_40, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_41, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_42, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_43, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_44, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_45, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_46, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_47, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_48, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_49, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_50, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_51, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_52, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_53, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_54, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_55, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_56, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_57, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_58, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_59, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_60, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_61, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_62, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_63, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_64, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_65, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_66, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_67, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_68, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_69, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_70, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_71, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_72, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_73, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_74, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_75, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_76, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_77, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_78, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_79, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_80, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_81, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_82, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_83, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_84, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_85, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_86, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_87, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_88, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_89, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_90, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_91, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_92, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_93, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_94, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_95, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_96, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_97, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_98, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_99, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_100, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_101, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_102, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_103, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_104, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_105, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_106, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_107, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_108, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_109, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_110, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_111, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_112, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_113, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_114, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_115, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_116, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_117, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_118, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_119, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_120, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_121, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_122, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_123, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_124, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_125, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_126, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_data_127, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.DEVICE_OP_READ_REPLY_bank, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_request_id, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_result, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_regstart, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_count, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_0, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_1, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_2, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_3, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_4, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_5, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_6, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_7, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_8, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_9, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_10, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_11, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_12, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_13, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_14, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_15, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_16, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_17, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_18, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_19, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_20, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_21, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_22, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_23, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_24, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_25, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_26, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_27, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_28, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_29, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_30, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_31, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_32, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_33, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_34, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_35, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_36, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_37, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_38, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_39, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_40, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_41, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_42, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_43, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_44, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_45, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_46, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_47, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_48, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_49, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_50, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_51, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_52, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_53, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_54, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_55, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_56, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_57, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_58, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_59, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_60, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_61, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_62, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_63, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_64, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_65, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_66, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_67, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_68, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_69, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_70, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_71, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_72, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_73, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_74, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_75, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_76, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_77, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_78, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_79, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_80, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_81, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_82, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_83, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_84, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_85, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_86, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_87, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_88, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_89, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_90, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_91, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_92, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_93, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_94, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_95, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_96, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_97, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_98, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_99, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_100, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_101, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_102, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_103, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_104, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_105, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_106, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_107, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_108, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_109, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_110, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_111, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_112, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_113, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_114, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_115, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_116, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_117, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_118, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_119, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_120, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_121, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_122, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_123, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_124, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_125, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_126, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_data_127, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_READ_REPLY_bank, tvbrange, value) end -- dissect payload of message type DEVICE_OP_WRITE function payload_fns.payload_11002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 180 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 180) @@ -13516,286 +14228,424 @@ function payload_fns.payload_11002(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_request_id, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_bustype, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_bus, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_address, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_busname, padded(field_offset, 40)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_regstart, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_count, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_0, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_1, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_2, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_3, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_4, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_5, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_6, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_7, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_8, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_9, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_10, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_11, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_12, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_13, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_14, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_15, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_16, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_17, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_18, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_19, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_20, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_21, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_22, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_23, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_24, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_25, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_26, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_27, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_28, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_29, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_30, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_31, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_32, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_33, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_34, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_35, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_36, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_37, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_38, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_39, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_40, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_41, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_42, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_43, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_44, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_45, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_46, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_47, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_48, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_49, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_50, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_51, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_52, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_53, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_54, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_55, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_56, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_57, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_58, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_59, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_60, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_61, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_62, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_63, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_64, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_65, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_66, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_67, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_68, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_69, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_70, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_71, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_72, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_73, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_74, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_75, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_76, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_77, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_78, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_79, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_80, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_81, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_82, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_83, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_84, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_85, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_86, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_87, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_88, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_89, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_90, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_91, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_92, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_93, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_94, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_95, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_96, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_97, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_98, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_99, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_100, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_101, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_102, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_103, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_104, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_105, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_106, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_107, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_108, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_109, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_110, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_111, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_112, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_113, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_114, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_115, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_116, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_117, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_118, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_119, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_120, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_121, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_122, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_123, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_124, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_125, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_126, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_data_127, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_bank, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_request_id, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_bustype, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_bus, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_address, tvbrange, value) + tvbrange = padded(offset + 9, 40) + value = tvbrange:string() + subtree = tree:add_le(f.DEVICE_OP_WRITE_busname, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_regstart, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_count, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_0, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_1, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_2, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_3, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_4, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_5, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_6, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_7, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_8, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_9, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_10, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_11, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_12, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_13, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_14, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_15, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_16, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_17, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_18, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_19, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_20, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_21, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_22, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_23, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_24, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_25, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_26, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_27, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_28, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_29, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_30, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_31, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_32, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_33, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_34, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_35, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_36, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_37, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_38, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_39, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_40, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_41, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_42, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_43, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_44, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_45, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_46, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_47, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_48, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_49, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_50, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_51, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_52, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_53, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_54, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_55, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_56, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_57, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_58, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_59, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_60, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_61, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_62, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_63, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_64, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_65, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_66, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_67, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_68, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_69, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_70, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_71, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_72, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_73, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_74, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_75, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_76, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_77, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_78, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_79, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_80, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_81, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_82, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_83, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_84, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_85, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_86, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_87, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_88, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_89, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_90, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_91, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_92, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_93, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_94, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_95, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_96, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_97, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_98, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_99, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_100, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_101, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_102, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_103, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_104, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_105, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_106, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_107, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_108, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_109, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_110, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_111, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_112, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_113, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_114, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_115, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_116, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_117, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_118, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_119, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_120, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_121, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_122, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_123, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_124, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_125, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_126, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_data_127, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_bank, tvbrange, value) end -- dissect payload of message type DEVICE_OP_WRITE_REPLY function payload_fns.payload_11003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -13803,14 +14653,16 @@ function payload_fns.payload_11003(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_REPLY_request_id, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DEVICE_OP_WRITE_REPLY_result, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_REPLY_request_id, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEVICE_OP_WRITE_REPLY_result, tvbrange, value) end -- dissect payload of message type SECURE_COMMAND function payload_fns.payload_11004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 232 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 232) @@ -13818,462 +14670,688 @@ function payload_fns.payload_11004(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.SECURE_COMMAND_target_system, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.SECURE_COMMAND_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SECURE_COMMAND_sequence, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SECURE_COMMAND_operation, padded(field_offset, 4)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_length, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.SECURE_COMMAND_sig_length, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_0, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_1, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_2, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_3, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_4, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_5, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_6, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_7, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_8, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_9, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_10, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_11, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_12, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_13, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_14, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_15, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_16, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_17, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_18, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_19, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_20, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_21, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_22, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_23, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_24, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_25, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_26, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_27, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_28, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_29, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_30, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_31, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_32, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_33, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_34, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_35, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_36, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_37, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_38, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_39, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_40, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_41, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_42, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_43, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_44, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_45, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_46, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_47, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_48, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_49, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_50, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_51, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_52, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_53, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_54, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_55, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_56, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_57, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_58, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_59, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_60, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_61, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_62, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_63, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_64, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_65, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_66, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_67, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_68, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_69, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_70, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_71, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_72, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_73, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_74, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_75, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_76, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_77, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_78, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_79, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_80, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_81, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_82, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_83, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_84, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_85, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_86, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_87, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_88, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_89, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_90, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_91, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_92, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_93, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_94, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_95, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_96, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_97, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_98, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_99, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_100, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_101, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_102, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_103, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_104, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_105, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_106, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_107, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_108, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_109, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_110, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_111, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_112, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_113, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_114, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_115, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_116, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_117, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_118, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_119, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_120, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_121, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_122, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_123, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_124, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_125, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_126, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_127, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_128, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_129, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_130, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_131, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_132, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_133, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_134, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_135, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_136, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_137, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_138, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_139, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_140, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_141, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_142, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_143, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_144, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_145, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_146, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_147, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_148, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_149, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_150, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_151, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_152, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_153, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_154, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_155, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_156, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_157, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_158, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_159, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_160, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_161, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_162, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_163, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_164, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_165, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_166, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_167, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_168, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_169, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_170, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_171, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_172, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_173, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_174, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_175, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_176, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_177, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_178, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_179, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_180, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_181, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_182, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_183, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_184, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_185, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_186, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_187, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_188, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_189, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_190, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_191, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_192, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_193, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_194, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_195, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_196, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_197, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_198, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_199, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_200, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_201, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_202, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_203, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_204, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_205, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_206, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_207, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_208, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_209, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_210, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_211, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_212, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_213, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_214, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_215, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_216, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_217, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_218, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.SECURE_COMMAND_data_219, padded(field_offset, 1)) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_sequence, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_operation, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_length, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_sig_length, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_0, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_1, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_2, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_3, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_4, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_5, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_6, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_7, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_8, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_9, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_10, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_11, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_12, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_13, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_14, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_15, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_16, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_17, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_18, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_19, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_20, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_21, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_22, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_23, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_24, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_25, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_26, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_27, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_28, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_29, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_30, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_31, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_32, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_33, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_34, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_35, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_36, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_37, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_38, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_39, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_40, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_41, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_42, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_43, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_44, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_45, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_46, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_47, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_48, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_49, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_50, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_51, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_52, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_53, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_54, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_55, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_56, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_57, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_58, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_59, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_60, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_61, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_62, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_63, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_64, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_65, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_66, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_67, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_68, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_69, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_70, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_71, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_72, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_73, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_74, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_75, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_76, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_77, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_78, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_79, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_80, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_81, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_82, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_83, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_84, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_85, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_86, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_87, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_88, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_89, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_90, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_91, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_92, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_93, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_94, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_95, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_96, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_97, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_98, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_99, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_100, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_101, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_102, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_103, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_104, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_105, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_106, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_107, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_108, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_109, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_110, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_111, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_112, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_113, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_114, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_115, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_116, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_117, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_118, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_119, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_120, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_121, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_122, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_123, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_124, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_125, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_126, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_127, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_128, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_129, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_130, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_131, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_132, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_133, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_134, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_135, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_136, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_137, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_138, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_139, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_140, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_141, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_142, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_143, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_144, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_145, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_146, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_147, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_148, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_149, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_150, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_151, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_152, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_153, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_154, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_155, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_156, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_157, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_158, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_159, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_160, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_161, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_162, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_163, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_164, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_165, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_166, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_167, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_168, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_169, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_170, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_171, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_172, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_173, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_174, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_175, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_176, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_177, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_178, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_179, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_180, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_181, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_182, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_183, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_184, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_185, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_186, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_187, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_188, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_189, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_190, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_191, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_192, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_193, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_194, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_195, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_196, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_197, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_198, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_199, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_200, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_201, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_202, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_203, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_204, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_205, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_206, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_207, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_208, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_209, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_210, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_211, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_212, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_213, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_214, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_215, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_216, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_217, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_218, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_data_219, tvbrange, value) end -- dissect payload of message type SECURE_COMMAND_REPLY function payload_fns.payload_11005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 230 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 230) @@ -14281,458 +15359,682 @@ function payload_fns.payload_11005(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_sequence, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_operation, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_result, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_length, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_0, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_1, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_2, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_3, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_4, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_5, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_6, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_7, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_8, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_9, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_10, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_11, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_12, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_13, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_14, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_15, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_16, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_17, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_18, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_19, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_20, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_21, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_22, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_23, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_24, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_25, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_26, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_27, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_28, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_29, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_30, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_31, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_32, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_33, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_34, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_35, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_36, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_37, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_38, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_39, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_40, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_41, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_42, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_43, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_44, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_45, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_46, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_47, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_48, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_49, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_50, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_51, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_52, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_53, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_54, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_55, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_56, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_57, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_58, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_59, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_60, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_61, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_62, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_63, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_64, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_65, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_66, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_67, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_68, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_69, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_70, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_71, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_72, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_73, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_74, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_75, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_76, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_77, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_78, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_79, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_80, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_81, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_82, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_83, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_84, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_85, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_86, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_87, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_88, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_89, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_90, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_91, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_92, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_93, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_94, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_95, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_96, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_97, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_98, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_99, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_100, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_101, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_102, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_103, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_104, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_105, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_106, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_107, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_108, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_109, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_110, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_111, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_112, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_113, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_114, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_115, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_116, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_117, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_118, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_119, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_120, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_121, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_122, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_123, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_124, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_125, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_126, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_127, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_128, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_129, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_130, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_131, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_132, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_133, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_134, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_135, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_136, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_137, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_138, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_139, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_140, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_141, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_142, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_143, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_144, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_145, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_146, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_147, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_148, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_149, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_150, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_151, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_152, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_153, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_154, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_155, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_156, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_157, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_158, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_159, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_160, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_161, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_162, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_163, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_164, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_165, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_166, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_167, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_168, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_169, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_170, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_171, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_172, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_173, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_174, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_175, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_176, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_177, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_178, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_179, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_180, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_181, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_182, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_183, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_184, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_185, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_186, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_187, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_188, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_189, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_190, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_191, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_192, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_193, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_194, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_195, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_196, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_197, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_198, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_199, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_200, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_201, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_202, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_203, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_204, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_205, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_206, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_207, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_208, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_209, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_210, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_211, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_212, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_213, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_214, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_215, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_216, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_217, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_218, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.SECURE_COMMAND_REPLY_data_219, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_sequence, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_operation, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_result, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_length, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_0, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_1, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_2, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_3, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_4, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_5, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_6, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_7, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_8, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_9, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_10, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_11, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_12, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_13, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_14, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_15, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_16, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_17, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_18, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_19, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_20, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_21, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_22, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_23, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_24, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_25, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_26, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_27, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_28, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_29, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_30, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_31, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_32, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_33, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_34, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_35, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_36, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_37, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_38, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_39, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_40, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_41, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_42, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_43, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_44, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_45, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_46, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_47, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_48, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_49, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_50, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_51, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_52, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_53, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_54, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_55, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_56, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_57, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_58, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_59, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_60, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_61, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_62, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_63, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_64, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_65, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_66, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_67, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_68, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_69, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_70, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_71, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_72, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_73, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_74, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_75, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_76, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_77, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_78, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_79, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_80, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_81, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_82, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_83, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_84, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_85, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_86, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_87, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_88, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_89, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_90, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_91, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_92, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_93, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_94, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_95, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_96, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_97, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_98, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_99, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_100, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_101, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_102, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_103, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_104, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_105, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_106, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_107, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_108, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_109, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_110, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_111, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_112, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_113, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_114, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_115, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_116, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_117, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_118, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_119, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_120, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_121, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_122, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_123, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_124, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_125, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_126, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_127, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_128, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_129, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_130, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_131, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_132, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_133, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_134, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_135, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_136, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_137, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_138, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_139, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_140, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_141, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_142, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_143, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_144, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_145, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_146, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_147, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_148, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_149, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_150, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_151, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_152, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_153, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_154, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_155, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_156, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_157, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_158, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_159, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_160, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_161, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_162, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_163, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_164, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_165, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_166, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_167, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_168, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_169, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_170, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_171, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_172, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_173, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_174, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_175, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_176, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_177, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_178, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_179, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_180, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_181, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_182, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_183, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_184, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_185, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_186, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_187, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_188, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_189, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_190, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_191, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_192, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_193, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_194, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_195, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_196, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_197, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_198, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_199, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_200, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_201, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_202, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_203, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_204, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_205, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_206, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_207, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_208, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_209, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_210, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_211, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_212, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_213, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_214, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_215, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_216, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_217, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_218, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SECURE_COMMAND_REPLY_data_219, tvbrange, value) end -- dissect payload of message type ADAP_TUNING function payload_fns.payload_11010(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 49 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 49) @@ -14740,36 +16042,49 @@ function payload_fns.payload_11010(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 48 - subtree, value = tree:add_le(f.ADAP_TUNING_axis, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ADAP_TUNING_desired, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ADAP_TUNING_achieved, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ADAP_TUNING_error, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ADAP_TUNING_theta, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ADAP_TUNING_omega, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ADAP_TUNING_sigma, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ADAP_TUNING_theta_dot, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ADAP_TUNING_omega_dot, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ADAP_TUNING_sigma_dot, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ADAP_TUNING_f, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ADAP_TUNING_f_dot, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ADAP_TUNING_u, padded(field_offset, 4)) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADAP_TUNING_axis, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_desired, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_achieved, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_error, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_theta, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_omega, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_sigma, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_theta_dot, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_omega_dot, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_sigma_dot, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_f, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_f_dot, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ADAP_TUNING_u, tvbrange, value) end -- dissect payload of message type VISION_POSITION_DELTA function payload_fns.payload_11011(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -14777,28 +16092,37 @@ function payload_fns.payload_11011(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_time_delta_usec, padded(field_offset, 8)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_angle_delta_0, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_angle_delta_1, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_angle_delta_2, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_position_delta_0, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_position_delta_1, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_position_delta_2, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.VISION_POSITION_DELTA_confidence, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VISION_POSITION_DELTA_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VISION_POSITION_DELTA_time_delta_usec, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_angle_delta_0, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_angle_delta_1, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_angle_delta_2, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_position_delta_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_position_delta_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_position_delta_2, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_DELTA_confidence, tvbrange, value) end -- dissect payload of message type AOA_SSA function payload_fns.payload_11020(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -14806,16 +16130,19 @@ function payload_fns.payload_11020(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AOA_SSA_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AOA_SSA_AOA, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AOA_SSA_SSA, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.AOA_SSA_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AOA_SSA_AOA, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AOA_SSA_SSA, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_1_TO_4 function payload_fns.payload_11030(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -14823,58 +16150,82 @@ function payload_fns.payload_11030(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_1_TO_4_count_3, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_5_TO_8 function payload_fns.payload_11031(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -14882,58 +16233,82 @@ function payload_fns.payload_11031(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_5_TO_8_count_3, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_9_TO_12 function payload_fns.payload_11032(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -14941,58 +16316,82 @@ function payload_fns.payload_11032(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_9_TO_12_count_3, tvbrange, value) end -- dissect payload of message type OSD_PARAM_CONFIG function payload_fns.payload_11033(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 37 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 37) @@ -15000,30 +16399,40 @@ function payload_fns.payload_11033(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 16 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_target_system, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_request_id, padded(field_offset, 4)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_osd_screen, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_osd_index, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_param_id, padded(field_offset, 16)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_config_type, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_min_value, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_max_value, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_increment, padded(field_offset, 4)) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_target_system, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_request_id, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_osd_screen, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_osd_index, tvbrange, value) + tvbrange = padded(offset + 20, 16) + value = tvbrange:string() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_param_id, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_config_type, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_min_value, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_max_value, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_increment, tvbrange, value) end -- dissect payload of message type OSD_PARAM_CONFIG_REPLY function payload_fns.payload_11034(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -15031,14 +16440,16 @@ function payload_fns.payload_11034(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_REPLY_request_id, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OSD_PARAM_CONFIG_REPLY_result, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_REPLY_request_id, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_CONFIG_REPLY_result, tvbrange, value) end -- dissect payload of message type OSD_PARAM_SHOW_CONFIG function payload_fns.payload_11035(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -15046,20 +16457,25 @@ function payload_fns.payload_11035(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_request_id, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_osd_screen, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_osd_index, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_request_id, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_osd_screen, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_osd_index, tvbrange, value) end -- dissect payload of message type OSD_PARAM_SHOW_CONFIG_REPLY function payload_fns.payload_11036(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 34 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 34) @@ -15067,24 +16483,31 @@ function payload_fns.payload_11036(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_request_id, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_result, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_param_id, padded(field_offset, 16)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_config_type, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_min_value, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_max_value, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_increment, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_request_id, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_result, tvbrange, value) + tvbrange = padded(offset + 17, 16) + value = tvbrange:string() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_param_id, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_config_type, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_min_value, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_max_value, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OSD_PARAM_SHOW_CONFIG_REPLY_increment, tvbrange, value) end -- dissect payload of message type OBSTACLE_DISTANCE_3D function payload_fns.payload_11037(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -15092,28 +16515,37 @@ function payload_fns.payload_11037(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_sensor_type, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_frame, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_obstacle_id, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_min_distance, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_3D_max_distance, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_sensor_type, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_frame, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_obstacle_id, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_min_distance, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_3D_max_distance, tvbrange, value) end -- dissect payload of message type WATER_DEPTH function payload_fns.payload_11038(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 38 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 38) @@ -15121,32 +16553,43 @@ function payload_fns.payload_11038(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.WATER_DEPTH_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.WATER_DEPTH_id, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.WATER_DEPTH_healthy, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.WATER_DEPTH_lat, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.WATER_DEPTH_lng, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.WATER_DEPTH_alt, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.WATER_DEPTH_roll, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.WATER_DEPTH_pitch, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.WATER_DEPTH_yaw, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.WATER_DEPTH_distance, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.WATER_DEPTH_temperature, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.WATER_DEPTH_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.WATER_DEPTH_id, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.WATER_DEPTH_healthy, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.WATER_DEPTH_lat, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.WATER_DEPTH_lng, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WATER_DEPTH_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WATER_DEPTH_roll, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WATER_DEPTH_pitch, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WATER_DEPTH_yaw, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WATER_DEPTH_distance, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WATER_DEPTH_temperature, tvbrange, value) end -- dissect payload of message type MCU_STATUS function payload_fns.payload_11039(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -15154,20 +16597,25 @@ function payload_fns.payload_11039(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.MCU_STATUS_id, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MCU_STATUS_MCU_temperature, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MCU_STATUS_MCU_voltage, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MCU_STATUS_MCU_voltage_min, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.MCU_STATUS_MCU_voltage_max, padded(field_offset, 2)) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MCU_STATUS_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MCU_STATUS_MCU_temperature, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MCU_STATUS_MCU_voltage, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MCU_STATUS_MCU_voltage_min, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MCU_STATUS_MCU_voltage_max, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_13_TO_16 function payload_fns.payload_11040(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -15175,58 +16623,82 @@ function payload_fns.payload_11040(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_13_TO_16_count_3, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_17_TO_20 function payload_fns.payload_11041(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -15234,58 +16706,82 @@ function payload_fns.payload_11041(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_17_TO_20_count_3, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_21_TO_24 function payload_fns.payload_11042(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -15293,58 +16789,82 @@ function payload_fns.payload_11042(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_21_TO_24_count_3, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_25_TO_28 function payload_fns.payload_11043(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -15352,58 +16872,82 @@ function payload_fns.payload_11043(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_25_TO_28_count_3, tvbrange, value) end -- dissect payload of message type ESC_TELEMETRY_29_TO_32 function payload_fns.payload_11044(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -15411,58 +16955,82 @@ function payload_fns.payload_11044(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_0, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_1, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_2, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_3, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_0, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_1, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_2, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_3, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_0, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_1, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_2, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_3, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_0, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_1, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_2, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_3, padded(field_offset, 2)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_0, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_temperature_3, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_voltage_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_current_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_0, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_1, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_2, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_totalcurrent_3, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_0, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_1, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_2, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_rpm_3, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_0, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_1, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_2, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESC_TELEMETRY_29_TO_32_count_3, tvbrange, value) end -- dissect payload of message type VIDEO_STREAM_INFORMATION99 function payload_fns.payload_26900(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 246 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 246) @@ -15470,26 +17038,34 @@ function payload_fns.payload_26900(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 14 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_camera_id, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_status, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_framerate, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_resolution_h, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_resolution_v, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_bitrate, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_rotation, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION99_uri, padded(field_offset, 230)) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_camera_id, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_status, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_framerate, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_resolution_h, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_resolution_v, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_bitrate, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_rotation, tvbrange, value) + tvbrange = padded(offset + 16, 230) + value = tvbrange:string() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION99_uri, tvbrange, value) end -- dissect payload of message type SYS_STATUS function payload_fns.payload_1(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 31 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 31) @@ -15497,39 +17073,52 @@ function payload_fns.payload_1(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SYS_STATUS_onboard_control_sensors_present, padded(field_offset, 4)) - dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_present", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SYS_STATUS_onboard_control_sensors_enabled, padded(field_offset, 4)) - dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_enabled", value) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SYS_STATUS_onboard_control_sensors_health, padded(field_offset, 4)) - dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_health", value) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SYS_STATUS_load, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SYS_STATUS_voltage_battery, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SYS_STATUS_current_battery, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.SYS_STATUS_battery_remaining, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SYS_STATUS_drop_rate_comm, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SYS_STATUS_errors_comm, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SYS_STATUS_errors_count1, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SYS_STATUS_errors_count2, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.SYS_STATUS_errors_count3, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SYS_STATUS_errors_count4, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_present, tvbrange, value) + dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_present", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_enabled, tvbrange, value) + dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_enabled", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_onboard_control_sensors_health, tvbrange, value) + dissect_flags_MAV_SYS_STATUS_SENSOR(subtree, "SYS_STATUS_onboard_control_sensors_health", tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_load, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_voltage_battery, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SYS_STATUS_current_battery, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.SYS_STATUS_battery_remaining, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_drop_rate_comm, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_comm, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count1, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count2, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count3, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYS_STATUS_errors_count4, tvbrange, value) end -- dissect payload of message type SYSTEM_TIME function payload_fns.payload_2(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 12 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 12) @@ -15537,14 +17126,16 @@ function payload_fns.payload_2(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SYSTEM_TIME_time_unix_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SYSTEM_TIME_time_boot_ms, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SYSTEM_TIME_time_unix_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SYSTEM_TIME_time_boot_ms, tvbrange, value) end -- dissect payload of message type PING function payload_fns.payload_4(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 14 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 14) @@ -15552,18 +17143,22 @@ function payload_fns.payload_4(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.PING_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.PING_seq, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.PING_target_system, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.PING_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.PING_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PING_seq, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PING_target_system, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PING_target_component, tvbrange, value) end -- dissect payload of message type CHANGE_OPERATOR_CONTROL function payload_fns.payload_5(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -15571,18 +17166,22 @@ function payload_fns.payload_5(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_control_request, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_version, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_passkey, padded(field_offset, 25)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_control_request, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_version, tvbrange, value) + tvbrange = padded(offset + 3, 25) + value = tvbrange:string() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_passkey, tvbrange, value) end -- dissect payload of message type CHANGE_OPERATOR_CONTROL_ACK function payload_fns.payload_6(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -15590,16 +17189,19 @@ function payload_fns.payload_6(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_gcs_system_id, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_control_request, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_ack, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_gcs_system_id, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_control_request, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CHANGE_OPERATOR_CONTROL_ACK_ack, tvbrange, value) end -- dissect payload of message type AUTH_KEY function payload_fns.payload_7(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 32 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 32) @@ -15607,12 +17209,13 @@ function payload_fns.payload_7(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AUTH_KEY_key, padded(field_offset, 32)) + tvbrange = padded(offset + 0, 32) + value = tvbrange:string() + subtree = tree:add_le(f.AUTH_KEY_key, tvbrange, value) end -- dissect payload of message type SET_MODE function payload_fns.payload_11(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -15620,16 +17223,19 @@ function payload_fns.payload_11(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_MODE_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.SET_MODE_base_mode, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_MODE_custom_mode, padded(field_offset, 4)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MODE_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MODE_base_mode, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_MODE_custom_mode, tvbrange, value) end -- dissect payload of message type PARAM_REQUEST_READ function payload_fns.payload_20(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -15637,18 +17243,22 @@ function payload_fns.payload_20(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.PARAM_REQUEST_READ_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.PARAM_REQUEST_READ_target_component, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.PARAM_REQUEST_READ_param_id, padded(field_offset, 16)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_REQUEST_READ_param_index, padded(field_offset, 2)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_READ_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_READ_target_component, tvbrange, value) + tvbrange = padded(offset + 4, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_REQUEST_READ_param_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.PARAM_REQUEST_READ_param_index, tvbrange, value) end -- dissect payload of message type PARAM_REQUEST_LIST function payload_fns.payload_21(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -15656,14 +17266,16 @@ function payload_fns.payload_21(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_REQUEST_LIST_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.PARAM_REQUEST_LIST_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_REQUEST_LIST_target_component, tvbrange, value) end -- dissect payload of message type PARAM_VALUE function payload_fns.payload_22(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 25 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 25) @@ -15671,20 +17283,25 @@ function payload_fns.payload_22(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.PARAM_VALUE_param_id, padded(field_offset, 16)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_VALUE_param_value, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.PARAM_VALUE_param_type, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.PARAM_VALUE_param_count, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.PARAM_VALUE_param_index, padded(field_offset, 2)) + tvbrange = padded(offset + 8, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_VALUE_param_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PARAM_VALUE_param_value, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_VALUE_param_type, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_VALUE_param_count, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_VALUE_param_index, tvbrange, value) end -- dissect payload of message type PARAM_SET function payload_fns.payload_23(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 23 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 23) @@ -15692,20 +17309,25 @@ function payload_fns.payload_23(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.PARAM_SET_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.PARAM_SET_target_component, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.PARAM_SET_param_id, padded(field_offset, 16)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_SET_param_value, padded(field_offset, 4)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.PARAM_SET_param_type, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_SET_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_SET_target_component, tvbrange, value) + tvbrange = padded(offset + 6, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_SET_param_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PARAM_SET_param_value, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_SET_param_type, tvbrange, value) end -- dissect payload of message type GPS_RAW_INT function payload_fns.payload_24(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 52 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 52) @@ -15713,42 +17335,58 @@ function payload_fns.payload_24(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_RAW_INT_time_usec, padded(field_offset, 8)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS_RAW_INT_fix_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_RAW_INT_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_RAW_INT_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS_RAW_INT_alt, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS_RAW_INT_eph, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.GPS_RAW_INT_epv, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS_RAW_INT_vel, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.GPS_RAW_INT_cog, padded(field_offset, 2)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.GPS_RAW_INT_satellites_visible, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS_RAW_INT_alt_ellipsoid, padded(field_offset, 4)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS_RAW_INT_h_acc, padded(field_offset, 4)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.GPS_RAW_INT_v_acc, padded(field_offset, 4)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.GPS_RAW_INT_vel_acc, padded(field_offset, 4)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.GPS_RAW_INT_hdg_acc, padded(field_offset, 4)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.GPS_RAW_INT_yaw, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GPS_RAW_INT_time_usec, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_fix_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RAW_INT_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RAW_INT_lon, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RAW_INT_alt, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_eph, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_epv, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_vel, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_cog, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_satellites_visible, tvbrange, value) + tvbrange = padded(offset + 30, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RAW_INT_alt_ellipsoid, tvbrange, value) + tvbrange = padded(offset + 34, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_h_acc, tvbrange, value) + tvbrange = padded(offset + 38, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_v_acc, tvbrange, value) + tvbrange = padded(offset + 42, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_vel_acc, tvbrange, value) + tvbrange = padded(offset + 46, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_hdg_acc, tvbrange, value) + tvbrange = padded(offset + 50, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_yaw, tvbrange, value) end -- dissect payload of message type GPS_STATUS function payload_fns.payload_25(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 101 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 101) @@ -15756,212 +17394,313 @@ function payload_fns.payload_25(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_STATUS_satellites_visible, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_0, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_1, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_2, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_3, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_4, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_5, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_6, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_7, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_8, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_9, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_10, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_11, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_12, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_13, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_14, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_15, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_16, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_17, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_18, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_prn_19, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_0, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_1, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_2, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_3, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_4, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_5, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_6, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_7, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_8, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_9, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_10, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_11, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_12, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_13, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_14, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_15, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_16, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_17, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_18, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_used_19, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_0, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_1, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_2, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_3, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_4, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_5, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_6, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_7, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_8, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_9, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_10, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_11, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_12, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_13, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_14, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_15, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_16, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_17, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_18, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_elevation_19, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_0, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_1, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_2, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_3, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_4, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_5, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_6, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_7, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_8, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_9, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_10, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_11, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_12, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_13, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_14, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_15, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_16, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_17, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_18, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_azimuth_19, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_0, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_1, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_2, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_3, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_4, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_5, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_6, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_7, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_8, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_9, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_10, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_11, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_12, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_13, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_14, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_15, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_16, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_17, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_18, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.GPS_STATUS_satellite_snr_19, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellites_visible, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_0, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_1, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_2, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_3, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_4, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_5, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_6, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_7, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_8, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_9, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_10, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_11, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_12, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_13, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_14, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_15, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_16, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_17, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_18, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_prn_19, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_0, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_1, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_2, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_3, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_4, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_5, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_6, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_7, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_8, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_9, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_10, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_11, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_12, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_13, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_14, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_15, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_16, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_17, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_18, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_used_19, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_0, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_1, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_2, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_3, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_4, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_5, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_6, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_7, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_8, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_9, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_10, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_11, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_12, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_13, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_14, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_15, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_16, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_17, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_18, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_elevation_19, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_0, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_1, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_2, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_3, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_4, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_5, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_6, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_7, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_8, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_9, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_10, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_11, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_12, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_13, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_14, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_15, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_16, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_17, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_18, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_azimuth_19, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_0, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_1, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_2, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_3, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_4, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_5, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_6, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_7, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_8, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_9, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_10, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_11, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_12, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_13, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_14, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_15, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_16, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_17, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_18, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_STATUS_satellite_snr_19, tvbrange, value) end -- dissect payload of message type SCALED_IMU function payload_fns.payload_26(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 24 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 24) @@ -15969,32 +17708,43 @@ function payload_fns.payload_26(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SCALED_IMU_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SCALED_IMU_xacc, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.SCALED_IMU_yacc, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SCALED_IMU_zacc, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SCALED_IMU_xgyro, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SCALED_IMU_ygyro, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SCALED_IMU_zgyro, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SCALED_IMU_xmag, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SCALED_IMU_ymag, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SCALED_IMU_zmag, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SCALED_IMU_temperature, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SCALED_IMU_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_xacc, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_yacc, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_zacc, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_xgyro, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_ygyro, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_zgyro, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_xmag, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_ymag, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_zmag, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU_temperature, tvbrange, value) end -- dissect payload of message type RAW_IMU function payload_fns.payload_27(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 29 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 29) @@ -16002,34 +17752,46 @@ function payload_fns.payload_27(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RAW_IMU_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RAW_IMU_xacc, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RAW_IMU_yacc, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RAW_IMU_zacc, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RAW_IMU_xgyro, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.RAW_IMU_ygyro, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RAW_IMU_zgyro, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.RAW_IMU_xmag, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.RAW_IMU_ymag, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.RAW_IMU_zmag, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.RAW_IMU_id, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.RAW_IMU_temperature, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.RAW_IMU_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_xacc, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_yacc, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_zacc, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_xgyro, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_ygyro, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_zgyro, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_xmag, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_ymag, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_zmag, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RAW_IMU_id, tvbrange, value) + tvbrange = padded(offset + 27, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_IMU_temperature, tvbrange, value) end -- dissect payload of message type RAW_PRESSURE function payload_fns.payload_28(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -16037,20 +17799,25 @@ function payload_fns.payload_28(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RAW_PRESSURE_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RAW_PRESSURE_press_abs, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RAW_PRESSURE_press_diff1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RAW_PRESSURE_press_diff2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RAW_PRESSURE_temperature, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.RAW_PRESSURE_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_PRESSURE_press_abs, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_PRESSURE_press_diff1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_PRESSURE_press_diff2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RAW_PRESSURE_temperature, tvbrange, value) end -- dissect payload of message type SCALED_PRESSURE function payload_fns.payload_29(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -16058,20 +17825,25 @@ function payload_fns.payload_29(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SCALED_PRESSURE_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SCALED_PRESSURE_press_abs, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SCALED_PRESSURE_press_diff, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SCALED_PRESSURE_temperature, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SCALED_PRESSURE_temperature_press_diff, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SCALED_PRESSURE_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SCALED_PRESSURE_press_abs, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SCALED_PRESSURE_press_diff, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_PRESSURE_temperature, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_PRESSURE_temperature_press_diff, tvbrange, value) end -- dissect payload of message type ATTITUDE function payload_fns.payload_30(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -16079,24 +17851,31 @@ function payload_fns.payload_30(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ATTITUDE_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ATTITUDE_roll, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ATTITUDE_pitch, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ATTITUDE_yaw, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ATTITUDE_rollspeed, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ATTITUDE_pitchspeed, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ATTITUDE_yawspeed, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ATTITUDE_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_roll, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_pitch, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_yaw, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_rollspeed, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_yawspeed, tvbrange, value) end -- dissect payload of message type ATTITUDE_QUATERNION function payload_fns.payload_31(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 48 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 48) @@ -16104,34 +17883,46 @@ function payload_fns.payload_31(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_q1, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_q2, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_q3, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_q4, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_rollspeed, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_pitchspeed, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_yawspeed, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_0, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_1, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_2, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_3, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_q1, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_q2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_q3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_q4, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_rollspeed, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_yawspeed, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_repr_offset_q_3, tvbrange, value) end -- dissect payload of message type LOCAL_POSITION_NED function payload_fns.payload_32(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -16139,24 +17930,31 @@ function payload_fns.payload_32(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_vx, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_vy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_vz, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOCAL_POSITION_NED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_vz, tvbrange, value) end -- dissect payload of message type GLOBAL_POSITION_INT function payload_fns.payload_33(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -16164,28 +17962,37 @@ function payload_fns.payload_33(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_lat, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_lon, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_alt, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_relative_alt, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_vx, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_vy, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_vz, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_hdg, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_lat, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_lon, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_relative_alt, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_vx, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_vy, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_vz, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_hdg, tvbrange, value) end -- dissect payload of message type RC_CHANNELS_SCALED function payload_fns.payload_34(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 22 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 22) @@ -16193,32 +18000,43 @@ function payload_fns.payload_34(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_port, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan1_scaled, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan2_scaled, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan3_scaled, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan4_scaled, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan5_scaled, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan6_scaled, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan7_scaled, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_chan8_scaled, padded(field_offset, 2)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.RC_CHANNELS_SCALED_rssi, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_port, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan1_scaled, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan2_scaled, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan3_scaled, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan4_scaled, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan5_scaled, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan6_scaled, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan7_scaled, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_chan8_scaled, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_SCALED_rssi, tvbrange, value) end -- dissect payload of message type RC_CHANNELS_RAW function payload_fns.payload_35(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 22 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 22) @@ -16226,32 +18044,43 @@ function payload_fns.payload_35(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_port, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan1_raw, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan2_raw, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan3_raw, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan4_raw, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan5_raw, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan6_raw, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan7_raw, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_chan8_raw, padded(field_offset, 2)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.RC_CHANNELS_RAW_rssi, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_port, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan1_raw, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan2_raw, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan3_raw, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan4_raw, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan5_raw, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan6_raw, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan7_raw, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_chan8_raw, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_RAW_rssi, tvbrange, value) end -- dissect payload of message type SERVO_OUTPUT_RAW function payload_fns.payload_36(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 37 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 37) @@ -16259,46 +18088,64 @@ function payload_fns.payload_36(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_time_usec, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_port, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo1_raw, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo2_raw, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo3_raw, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo4_raw, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo5_raw, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo6_raw, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo7_raw, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo8_raw, padded(field_offset, 2)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo9_raw, padded(field_offset, 2)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo10_raw, padded(field_offset, 2)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo11_raw, padded(field_offset, 2)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo12_raw, padded(field_offset, 2)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo13_raw, padded(field_offset, 2)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo14_raw, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo15_raw, padded(field_offset, 2)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.SERVO_OUTPUT_RAW_servo16_raw, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_time_usec, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_port, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo1_raw, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo2_raw, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo3_raw, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo4_raw, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo5_raw, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo6_raw, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo7_raw, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo8_raw, tvbrange, value) + tvbrange = padded(offset + 21, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo9_raw, tvbrange, value) + tvbrange = padded(offset + 23, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo10_raw, tvbrange, value) + tvbrange = padded(offset + 25, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo11_raw, tvbrange, value) + tvbrange = padded(offset + 27, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo12_raw, tvbrange, value) + tvbrange = padded(offset + 29, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo13_raw, tvbrange, value) + tvbrange = padded(offset + 31, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo14_raw, tvbrange, value) + tvbrange = padded(offset + 33, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo15_raw, tvbrange, value) + tvbrange = padded(offset + 35, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERVO_OUTPUT_RAW_servo16_raw, tvbrange, value) end -- dissect payload of message type MISSION_REQUEST_PARTIAL_LIST function payload_fns.payload_37(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 7 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 7) @@ -16306,20 +18153,25 @@ function payload_fns.payload_37(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_start_index, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_end_index, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_start_index, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_end_index, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_PARTIAL_LIST_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_WRITE_PARTIAL_LIST function payload_fns.payload_38(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 7 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 7) @@ -16327,20 +18179,25 @@ function payload_fns.payload_38(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_start_index, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_end_index, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_start_index, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_end_index, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_WRITE_PARTIAL_LIST_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_ITEM function payload_fns.payload_39(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 38 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 38) @@ -16348,40 +18205,55 @@ function payload_fns.payload_39(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 32 - subtree, value = tree:add_le(f.MISSION_ITEM_target_system, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.MISSION_ITEM_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.MISSION_ITEM_seq, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.MISSION_ITEM_frame, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.MISSION_ITEM_command, padded(field_offset, 2)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.MISSION_ITEM_current, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.MISSION_ITEM_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_ITEM_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_ITEM_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MISSION_ITEM_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.MISSION_ITEM_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MISSION_ITEM_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.MISSION_ITEM_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.MISSION_ITEM_z, padded(field_offset, 4)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.MISSION_ITEM_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_target_system, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_seq, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_frame, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_command, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_current, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_z, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_REQUEST function payload_fns.payload_40(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -16389,18 +18261,22 @@ function payload_fns.payload_40(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_REQUEST_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MISSION_REQUEST_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_REQUEST_seq, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_REQUEST_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_seq, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_SET_CURRENT function payload_fns.payload_41(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 4 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 4) @@ -16408,29 +18284,42 @@ function payload_fns.payload_41(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_SET_CURRENT_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MISSION_SET_CURRENT_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_SET_CURRENT_seq, padded(field_offset, 2)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_SET_CURRENT_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_SET_CURRENT_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_SET_CURRENT_seq, tvbrange, value) end -- dissect payload of message type MISSION_CURRENT function payload_fns.payload_42(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree - if (offset + 2 > limit) then + local padded, field_offset, value, subtree, tvbrange + if (offset + 6 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 2) + padded:set_size(offset + 6) padded = padded:tvb("Untruncated payload") else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_CURRENT_seq, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CURRENT_seq, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CURRENT_total, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CURRENT_mission_state, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CURRENT_mission_mode, tvbrange, value) end -- dissect payload of message type MISSION_REQUEST_LIST function payload_fns.payload_43(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -16438,16 +18327,19 @@ function payload_fns.payload_43(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_REQUEST_LIST_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.MISSION_REQUEST_LIST_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_REQUEST_LIST_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_LIST_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_LIST_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_COUNT function payload_fns.payload_44(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -16455,18 +18347,22 @@ function payload_fns.payload_44(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_COUNT_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MISSION_COUNT_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_COUNT_count, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_COUNT_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_COUNT_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_COUNT_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_COUNT_count, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_COUNT_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_CLEAR_ALL function payload_fns.payload_45(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 3 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 3) @@ -16474,16 +18370,19 @@ function payload_fns.payload_45(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_CLEAR_ALL_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.MISSION_CLEAR_ALL_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_CLEAR_ALL_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CLEAR_ALL_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CLEAR_ALL_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_CLEAR_ALL_mission_type, tvbrange, value) end -- dissect payload of message type MISSION_ITEM_REACHED function payload_fns.payload_46(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -16491,12 +18390,13 @@ function payload_fns.payload_46(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_ITEM_REACHED_seq, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_REACHED_seq, tvbrange, value) end -- dissect payload of message type MISSION_ACK function payload_fns.payload_47(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 4 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 4) @@ -16504,18 +18404,22 @@ function payload_fns.payload_47(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_ACK_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.MISSION_ACK_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_ACK_type, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MISSION_ACK_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ACK_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ACK_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ACK_type, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ACK_mission_type, tvbrange, value) end -- dissect payload of message type SET_GPS_GLOBAL_ORIGIN function payload_fns.payload_48(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 21 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 21) @@ -16523,20 +18427,25 @@ function payload_fns.payload_48(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 12 - subtree, value = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_target_system, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_longitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_altitude, padded(field_offset, 4)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_time_usec, padded(field_offset, 8)) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_target_system, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_altitude, tvbrange, value) + tvbrange = padded(offset + 13, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SET_GPS_GLOBAL_ORIGIN_time_usec, tvbrange, value) end -- dissect payload of message type GPS_GLOBAL_ORIGIN function payload_fns.payload_49(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -16544,18 +18453,22 @@ function payload_fns.payload_49(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_GLOBAL_ORIGIN_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GPS_GLOBAL_ORIGIN_longitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_GLOBAL_ORIGIN_altitude, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_GLOBAL_ORIGIN_time_usec, padded(field_offset, 8)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_GLOBAL_ORIGIN_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_GLOBAL_ORIGIN_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_GLOBAL_ORIGIN_altitude, tvbrange, value) + tvbrange = padded(offset + 12, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GPS_GLOBAL_ORIGIN_time_usec, tvbrange, value) end -- dissect payload of message type PARAM_MAP_RC function payload_fns.payload_50(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 37 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 37) @@ -16563,28 +18476,37 @@ function payload_fns.payload_50(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 18 - subtree, value = tree:add_le(f.PARAM_MAP_RC_target_system, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.PARAM_MAP_RC_target_component, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.PARAM_MAP_RC_param_id, padded(field_offset, 16)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.PARAM_MAP_RC_param_index, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.PARAM_MAP_RC_parameter_rc_channel_index, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_MAP_RC_param_value0, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.PARAM_MAP_RC_scale, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.PARAM_MAP_RC_param_value_min, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.PARAM_MAP_RC_param_value_max, padded(field_offset, 4)) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_MAP_RC_target_system, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_MAP_RC_target_component, tvbrange, value) + tvbrange = padded(offset + 20, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_MAP_RC_param_id, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.PARAM_MAP_RC_param_index, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_MAP_RC_parameter_rc_channel_index, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PARAM_MAP_RC_param_value0, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PARAM_MAP_RC_scale, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PARAM_MAP_RC_param_value_min, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.PARAM_MAP_RC_param_value_max, tvbrange, value) end -- dissect payload of message type MISSION_REQUEST_INT function payload_fns.payload_51(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -16592,18 +18514,22 @@ function payload_fns.payload_51(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.MISSION_REQUEST_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MISSION_REQUEST_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_REQUEST_INT_seq, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_REQUEST_INT_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_INT_seq, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_REQUEST_INT_mission_type, tvbrange, value) end -- dissect payload of message type SAFETY_SET_ALLOWED_AREA function payload_fns.payload_54(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 27 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 27) @@ -16611,28 +18537,37 @@ function payload_fns.payload_54(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 24 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_target_system, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_target_component, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_frame, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p1x, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p1y, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p1z, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p2x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p2y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p2z, padded(field_offset, 4)) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_target_system, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_target_component, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_frame, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p1x, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p1y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p1z, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p2x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p2y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_SET_ALLOWED_AREA_p2z, tvbrange, value) end -- dissect payload of message type SAFETY_ALLOWED_AREA function payload_fns.payload_55(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 25 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 25) @@ -16640,24 +18575,31 @@ function payload_fns.payload_55(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 24 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_frame, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_p1x, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_p1y, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_p1z, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_p2x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_p2y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SAFETY_ALLOWED_AREA_p2z, padded(field_offset, 4)) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_frame, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_p1x, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_p1y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_p1z, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_p2x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_p2y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SAFETY_ALLOWED_AREA_p2z, tvbrange, value) end -- dissect payload of message type ATTITUDE_QUATERNION_COV function payload_fns.payload_61(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 72 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 72) @@ -16665,44 +18607,61 @@ function payload_fns.payload_61(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_0, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_1, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_2, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_3, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_rollspeed, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_pitchspeed, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_yawspeed, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_0, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_1, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_2, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_3, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_4, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_5, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_6, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_7, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_8, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_q_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_rollspeed, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_yawspeed, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_0, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_1, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_2, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_3, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_4, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_5, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_6, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_7, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_QUATERNION_COV_covariance_8, tvbrange, value) end -- dissect payload of message type NAV_CONTROLLER_OUTPUT function payload_fns.payload_62(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 26 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 26) @@ -16710,26 +18669,34 @@ function payload_fns.payload_62(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_nav_roll, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_nav_pitch, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_nav_bearing, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_target_bearing, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_wp_dist, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_alt_error, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_aspd_error, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.NAV_CONTROLLER_OUTPUT_xtrack_error, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_nav_roll, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_nav_pitch, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_nav_bearing, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_target_bearing, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_wp_dist, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_alt_error, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_aspd_error, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAV_CONTROLLER_OUTPUT_xtrack_error, tvbrange, value) end -- dissect payload of message type GLOBAL_POSITION_INT_COV function payload_fns.payload_63(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 181 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 181) @@ -16737,100 +18704,145 @@ function payload_fns.payload_63(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_time_usec, padded(field_offset, 8)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_estimator_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_alt, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_relative_alt, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_vx, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_vy, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_vz, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_0, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_1, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_2, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_3, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_4, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_5, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_6, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_7, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_8, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_9, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_10, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_11, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_12, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_13, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_14, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_15, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_16, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_17, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_18, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_19, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_20, padded(field_offset, 4)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_21, padded(field_offset, 4)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_22, padded(field_offset, 4)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_23, padded(field_offset, 4)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_24, padded(field_offset, 4)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_25, padded(field_offset, 4)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_26, padded(field_offset, 4)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_27, padded(field_offset, 4)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_28, padded(field_offset, 4)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_29, padded(field_offset, 4)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_30, padded(field_offset, 4)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_31, padded(field_offset, 4)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_32, padded(field_offset, 4)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_33, padded(field_offset, 4)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_34, padded(field_offset, 4)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_35, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_time_usec, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_estimator_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_lon, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_alt, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_relative_alt, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_vx, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_vy, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_vz, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_0, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_1, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_2, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_3, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_4, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_5, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_6, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_7, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_8, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_9, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_10, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_11, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_12, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_13, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_14, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_15, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_16, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_17, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_18, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_19, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_20, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_21, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_22, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_23, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_24, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_25, tvbrange, value) + tvbrange = padded(offset + 140, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_26, tvbrange, value) + tvbrange = padded(offset + 144, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_27, tvbrange, value) + tvbrange = padded(offset + 148, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_28, tvbrange, value) + tvbrange = padded(offset + 152, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_29, tvbrange, value) + tvbrange = padded(offset + 156, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_30, tvbrange, value) + tvbrange = padded(offset + 160, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_31, tvbrange, value) + tvbrange = padded(offset + 164, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_32, tvbrange, value) + tvbrange = padded(offset + 168, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_33, tvbrange, value) + tvbrange = padded(offset + 172, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_34, tvbrange, value) + tvbrange = padded(offset + 176, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_POSITION_INT_COV_covariance_35, tvbrange, value) end -- dissect payload of message type LOCAL_POSITION_NED_COV function payload_fns.payload_64(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 225 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 225) @@ -16838,122 +18850,178 @@ function payload_fns.payload_64(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_time_usec, padded(field_offset, 8)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_estimator_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_vx, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_vy, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_vz, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_ax, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_ay, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_az, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_0, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_1, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_2, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_3, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_4, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_5, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_6, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_7, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_8, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_9, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_10, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_11, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_12, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_13, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_14, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_15, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_16, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_17, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_18, padded(field_offset, 4)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_19, padded(field_offset, 4)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_20, padded(field_offset, 4)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_21, padded(field_offset, 4)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_22, padded(field_offset, 4)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_23, padded(field_offset, 4)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_24, padded(field_offset, 4)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_25, padded(field_offset, 4)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_26, padded(field_offset, 4)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_27, padded(field_offset, 4)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_28, padded(field_offset, 4)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_29, padded(field_offset, 4)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_30, padded(field_offset, 4)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_31, padded(field_offset, 4)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_32, padded(field_offset, 4)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_33, padded(field_offset, 4)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_34, padded(field_offset, 4)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_35, padded(field_offset, 4)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_36, padded(field_offset, 4)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_37, padded(field_offset, 4)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_38, padded(field_offset, 4)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_39, padded(field_offset, 4)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_40, padded(field_offset, 4)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_41, padded(field_offset, 4)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_42, padded(field_offset, 4)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_43, padded(field_offset, 4)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_44, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_time_usec, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_estimator_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_vx, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_vy, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_vz, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_ax, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_ay, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_az, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_0, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_1, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_2, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_3, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_4, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_5, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_6, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_7, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_8, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_9, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_10, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_11, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_12, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_13, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_14, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_15, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_16, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_17, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_18, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_19, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_20, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_21, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_22, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_23, tvbrange, value) + tvbrange = padded(offset + 140, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_24, tvbrange, value) + tvbrange = padded(offset + 144, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_25, tvbrange, value) + tvbrange = padded(offset + 148, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_26, tvbrange, value) + tvbrange = padded(offset + 152, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_27, tvbrange, value) + tvbrange = padded(offset + 156, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_28, tvbrange, value) + tvbrange = padded(offset + 160, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_29, tvbrange, value) + tvbrange = padded(offset + 164, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_30, tvbrange, value) + tvbrange = padded(offset + 168, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_31, tvbrange, value) + tvbrange = padded(offset + 172, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_32, tvbrange, value) + tvbrange = padded(offset + 176, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_33, tvbrange, value) + tvbrange = padded(offset + 180, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_34, tvbrange, value) + tvbrange = padded(offset + 184, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_35, tvbrange, value) + tvbrange = padded(offset + 188, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_36, tvbrange, value) + tvbrange = padded(offset + 192, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_37, tvbrange, value) + tvbrange = padded(offset + 196, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_38, tvbrange, value) + tvbrange = padded(offset + 200, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_39, tvbrange, value) + tvbrange = padded(offset + 204, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_40, tvbrange, value) + tvbrange = padded(offset + 208, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_41, tvbrange, value) + tvbrange = padded(offset + 212, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_42, tvbrange, value) + tvbrange = padded(offset + 216, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_43, tvbrange, value) + tvbrange = padded(offset + 220, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_COV_covariance_44, tvbrange, value) end -- dissect payload of message type RC_CHANNELS function payload_fns.payload_65(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -16961,52 +19029,73 @@ function payload_fns.payload_65(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RC_CHANNELS_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.RC_CHANNELS_chancount, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RC_CHANNELS_chan1_raw, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RC_CHANNELS_chan2_raw, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RC_CHANNELS_chan3_raw, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RC_CHANNELS_chan4_raw, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RC_CHANNELS_chan5_raw, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RC_CHANNELS_chan6_raw, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.RC_CHANNELS_chan7_raw, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RC_CHANNELS_chan8_raw, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.RC_CHANNELS_chan9_raw, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.RC_CHANNELS_chan10_raw, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.RC_CHANNELS_chan11_raw, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.RC_CHANNELS_chan12_raw, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.RC_CHANNELS_chan13_raw, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.RC_CHANNELS_chan14_raw, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.RC_CHANNELS_chan15_raw, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.RC_CHANNELS_chan16_raw, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.RC_CHANNELS_chan17_raw, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.RC_CHANNELS_chan18_raw, padded(field_offset, 2)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.RC_CHANNELS_rssi, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chancount, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan1_raw, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan2_raw, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan3_raw, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan4_raw, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan5_raw, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan6_raw, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan7_raw, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan8_raw, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan9_raw, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan10_raw, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan11_raw, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan12_raw, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan13_raw, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan14_raw, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan15_raw, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan16_raw, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan17_raw, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_chan18_raw, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_rssi, tvbrange, value) end -- dissect payload of message type REQUEST_DATA_STREAM function payload_fns.payload_66(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -17014,20 +19103,25 @@ function payload_fns.payload_66(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.REQUEST_DATA_STREAM_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.REQUEST_DATA_STREAM_target_component, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.REQUEST_DATA_STREAM_req_stream_id, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.REQUEST_DATA_STREAM_req_message_rate, padded(field_offset, 2)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.REQUEST_DATA_STREAM_start_stop, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REQUEST_DATA_STREAM_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REQUEST_DATA_STREAM_target_component, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REQUEST_DATA_STREAM_req_stream_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REQUEST_DATA_STREAM_req_message_rate, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.REQUEST_DATA_STREAM_start_stop, tvbrange, value) end -- dissect payload of message type DATA_STREAM function payload_fns.payload_67(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 4 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 4) @@ -17035,16 +19129,19 @@ function payload_fns.payload_67(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.DATA_STREAM_stream_id, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DATA_STREAM_message_rate, padded(field_offset, 2)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.DATA_STREAM_on_off, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_STREAM_stream_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_STREAM_message_rate, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_STREAM_on_off, tvbrange, value) end -- dissect payload of message type MANUAL_CONTROL function payload_fns.payload_69(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 11 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 11) @@ -17052,22 +19149,28 @@ function payload_fns.payload_69(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 10 - subtree, value = tree:add_le(f.MANUAL_CONTROL_target, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MANUAL_CONTROL_x, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MANUAL_CONTROL_y, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MANUAL_CONTROL_z, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.MANUAL_CONTROL_r, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MANUAL_CONTROL_buttons, padded(field_offset, 2)) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_CONTROL_target, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_x, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_y, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_z, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.MANUAL_CONTROL_r, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_CONTROL_buttons, tvbrange, value) end -- dissect payload of message type RC_CHANNELS_OVERRIDE function payload_fns.payload_70(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 38 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 38) @@ -17075,50 +19178,70 @@ function payload_fns.payload_70(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 16 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_target_system, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan1_raw, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan2_raw, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan3_raw, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan4_raw, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan5_raw, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan6_raw, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan7_raw, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan8_raw, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan9_raw, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan10_raw, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan11_raw, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan12_raw, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan13_raw, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan14_raw, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan15_raw, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan16_raw, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan17_raw, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan18_raw, padded(field_offset, 2)) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_target_system, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan1_raw, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan2_raw, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan3_raw, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan4_raw, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan5_raw, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan6_raw, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan7_raw, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan8_raw, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan9_raw, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan10_raw, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan11_raw, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan12_raw, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan13_raw, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan14_raw, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan15_raw, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan16_raw, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan17_raw, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RC_CHANNELS_OVERRIDE_chan18_raw, tvbrange, value) end -- dissect payload of message type MISSION_ITEM_INT function payload_fns.payload_73(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 38 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 38) @@ -17126,40 +19249,55 @@ function payload_fns.payload_73(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 32 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_seq, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_frame, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_command, padded(field_offset, 2)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_current, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_z, padded(field_offset, 4)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.MISSION_ITEM_INT_mission_type, padded(field_offset, 1)) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_seq, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_frame, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_command, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_current, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MISSION_ITEM_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MISSION_ITEM_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MISSION_ITEM_INT_z, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MISSION_ITEM_INT_mission_type, tvbrange, value) end -- dissect payload of message type VFR_HUD function payload_fns.payload_74(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -17167,22 +19305,28 @@ function payload_fns.payload_74(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.VFR_HUD_airspeed, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.VFR_HUD_groundspeed, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VFR_HUD_heading, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.VFR_HUD_throttle, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VFR_HUD_alt, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VFR_HUD_climb, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VFR_HUD_airspeed, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VFR_HUD_groundspeed, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.VFR_HUD_heading, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VFR_HUD_throttle, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VFR_HUD_alt, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VFR_HUD_climb, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_WAYPOINT function payload_fns.payload_75_cmd16(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17190,36 +19334,49 @@ function payload_fns.payload_75_cmd16(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LOITER_UNLIM function payload_fns.payload_75_cmd17(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17227,36 +19384,49 @@ function payload_fns.payload_75_cmd17(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LOITER_TURNS function payload_fns.payload_75_cmd18(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17264,36 +19434,49 @@ function payload_fns.payload_75_cmd18(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LOITER_TIME function payload_fns.payload_75_cmd19(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17301,36 +19484,49 @@ function payload_fns.payload_75_cmd19(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_RETURN_TO_LAUNCH function payload_fns.payload_75_cmd20(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17338,36 +19534,49 @@ function payload_fns.payload_75_cmd20(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LAND function payload_fns.payload_75_cmd21(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17375,36 +19584,49 @@ function payload_fns.payload_75_cmd21(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_TAKEOFF function payload_fns.payload_75_cmd22(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17412,36 +19634,49 @@ function payload_fns.payload_75_cmd22(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LAND_LOCAL function payload_fns.payload_75_cmd23(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17449,36 +19684,49 @@ function payload_fns.payload_75_cmd23(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_TAKEOFF_LOCAL function payload_fns.payload_75_cmd24(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17486,36 +19734,49 @@ function payload_fns.payload_75_cmd24(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_FOLLOW function payload_fns.payload_75_cmd25(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17523,36 +19784,49 @@ function payload_fns.payload_75_cmd25(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT function payload_fns.payload_75_cmd30(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17560,36 +19834,49 @@ function payload_fns.payload_75_cmd30(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LOITER_TO_ALT function payload_fns.payload_75_cmd31(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17597,36 +19884,49 @@ function payload_fns.payload_75_cmd31(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_FOLLOW function payload_fns.payload_75_cmd32(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17634,36 +19934,49 @@ function payload_fns.payload_75_cmd32(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_FOLLOW_REPOSITION function payload_fns.payload_75_cmd33(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17671,36 +19984,49 @@ function payload_fns.payload_75_cmd33(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_ROI function payload_fns.payload_75_cmd80(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17708,36 +20034,49 @@ function payload_fns.payload_75_cmd80(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_PATHPLANNING function payload_fns.payload_75_cmd81(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17745,36 +20084,49 @@ function payload_fns.payload_75_cmd81(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_SPLINE_WAYPOINT function payload_fns.payload_75_cmd82(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17782,36 +20134,49 @@ function payload_fns.payload_75_cmd82(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_ALTITUDE_WAIT function payload_fns.payload_75_cmd83(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17819,36 +20184,49 @@ function payload_fns.payload_75_cmd83(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_VTOL_TAKEOFF function payload_fns.payload_75_cmd84(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17856,36 +20234,49 @@ function payload_fns.payload_75_cmd84(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_VTOL_LAND function payload_fns.payload_75_cmd85(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17893,36 +20284,49 @@ function payload_fns.payload_75_cmd85(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_GUIDED_ENABLE function payload_fns.payload_75_cmd92(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17930,36 +20334,49 @@ function payload_fns.payload_75_cmd92(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_GUIDED_ENABLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_GUIDED_ENABLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_DELAY function payload_fns.payload_75_cmd93(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -17967,36 +20384,49 @@ function payload_fns.payload_75_cmd93(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_PAYLOAD_PLACE function payload_fns.payload_75_cmd94(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18004,36 +20434,49 @@ function payload_fns.payload_75_cmd94(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_LAST function payload_fns.payload_75_cmd95(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18041,36 +20484,49 @@ function payload_fns.payload_75_cmd95(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CONDITION_DELAY function payload_fns.payload_75_cmd112(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18078,36 +20534,49 @@ function payload_fns.payload_75_cmd112(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_DELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CONDITION_CHANGE_ALT function payload_fns.payload_75_cmd113(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18115,36 +20584,49 @@ function payload_fns.payload_75_cmd113(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CONDITION_DISTANCE function payload_fns.payload_75_cmd114(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18152,36 +20634,49 @@ function payload_fns.payload_75_cmd114(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_DISTANCE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DISTANCE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CONDITION_YAW function payload_fns.payload_75_cmd115(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18189,36 +20684,49 @@ function payload_fns.payload_75_cmd115(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CONDITION_LAST function payload_fns.payload_75_cmd159(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18226,36 +20734,49 @@ function payload_fns.payload_75_cmd159(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_MODE function payload_fns.payload_75_cmd176(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18263,36 +20784,49 @@ function payload_fns.payload_75_cmd176(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_JUMP function payload_fns.payload_75_cmd177(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18300,36 +20834,49 @@ function payload_fns.payload_75_cmd177(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_CHANGE_SPEED function payload_fns.payload_75_cmd178(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18337,36 +20884,49 @@ function payload_fns.payload_75_cmd178(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_HOME function payload_fns.payload_75_cmd179(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18374,36 +20934,49 @@ function payload_fns.payload_75_cmd179(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_PARAMETER function payload_fns.payload_75_cmd180(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18411,36 +20984,49 @@ function payload_fns.payload_75_cmd180(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_RELAY function payload_fns.payload_75_cmd181(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18448,36 +21034,49 @@ function payload_fns.payload_75_cmd181(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_REPEAT_RELAY function payload_fns.payload_75_cmd182(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18485,36 +21084,49 @@ function payload_fns.payload_75_cmd182(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_SERVO function payload_fns.payload_75_cmd183(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18522,36 +21134,49 @@ function payload_fns.payload_75_cmd183(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_REPEAT_SERVO function payload_fns.payload_75_cmd184(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18559,36 +21184,49 @@ function payload_fns.payload_75_cmd184(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_FLIGHTTERMINATION function payload_fns.payload_75_cmd185(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18596,36 +21234,49 @@ function payload_fns.payload_75_cmd185(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FLIGHTTERMINATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FLIGHTTERMINATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_CHANGE_ALTITUDE function payload_fns.payload_75_cmd186(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18633,36 +21284,49 @@ function payload_fns.payload_75_cmd186(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_LAND_START function payload_fns.payload_75_cmd189(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18670,36 +21334,49 @@ function payload_fns.payload_75_cmd189(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_RALLY_LAND function payload_fns.payload_75_cmd190(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18707,36 +21384,49 @@ function payload_fns.payload_75_cmd190(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GO_AROUND function payload_fns.payload_75_cmd191(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18744,36 +21434,49 @@ function payload_fns.payload_75_cmd191(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GO_AROUND_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GO_AROUND_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_REPOSITION function payload_fns.payload_75_cmd192(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18781,37 +21484,50 @@ function payload_fns.payload_75_cmd192(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param2, padded(field_offset, 4)) - dissect_flags_MAV_DO_REPOSITION_FLAGS(subtree, "cmd_MAV_CMD_DO_REPOSITION_param2", value) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param2, tvbrange, value) + dissect_flags_MAV_DO_REPOSITION_FLAGS(subtree, "cmd_MAV_CMD_DO_REPOSITION_param2", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_PAUSE_CONTINUE function payload_fns.payload_75_cmd193(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18819,36 +21535,49 @@ function payload_fns.payload_75_cmd193(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_PAUSE_CONTINUE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_PAUSE_CONTINUE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_REVERSE function payload_fns.payload_75_cmd194(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18856,36 +21585,49 @@ function payload_fns.payload_75_cmd194(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_REVERSE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_REVERSE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_ROI_LOCATION function payload_fns.payload_75_cmd195(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18893,36 +21635,49 @@ function payload_fns.payload_75_cmd195(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET function payload_fns.payload_75_cmd196(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18930,36 +21685,49 @@ function payload_fns.payload_75_cmd196(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_ROI_NONE function payload_fns.payload_75_cmd197(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -18967,36 +21735,49 @@ function payload_fns.payload_75_cmd197(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_ROI_SYSID function payload_fns.payload_75_cmd198(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19004,36 +21785,49 @@ function payload_fns.payload_75_cmd198(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_SYSID_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_SYSID_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_CONTROL_VIDEO function payload_fns.payload_75_cmd200(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19041,36 +21835,49 @@ function payload_fns.payload_75_cmd200(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_ROI function payload_fns.payload_75_cmd201(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19078,36 +21885,49 @@ function payload_fns.payload_75_cmd201(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_DIGICAM_CONFIGURE function payload_fns.payload_75_cmd202(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19115,36 +21935,49 @@ function payload_fns.payload_75_cmd202(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_DIGICAM_CONTROL function payload_fns.payload_75_cmd203(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19152,36 +21985,49 @@ function payload_fns.payload_75_cmd203(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_MOUNT_CONFIGURE function payload_fns.payload_75_cmd204(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19189,36 +22035,49 @@ function payload_fns.payload_75_cmd204(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_MOUNT_CONTROL function payload_fns.payload_75_cmd205(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19226,36 +22085,49 @@ function payload_fns.payload_75_cmd205(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_CAM_TRIGG_DIST function payload_fns.payload_75_cmd206(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19263,36 +22135,49 @@ function payload_fns.payload_75_cmd206(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_FENCE_ENABLE function payload_fns.payload_75_cmd207(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19300,36 +22185,49 @@ function payload_fns.payload_75_cmd207(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_PARACHUTE function payload_fns.payload_75_cmd208(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19337,36 +22235,49 @@ function payload_fns.payload_75_cmd208(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_PARACHUTE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_PARACHUTE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_MOTOR_TEST function payload_fns.payload_75_cmd209(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19374,36 +22285,49 @@ function payload_fns.payload_75_cmd209(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_INVERTED_FLIGHT function payload_fns.payload_75_cmd210(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19411,36 +22335,49 @@ function payload_fns.payload_75_cmd210(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_INVERTED_FLIGHT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_INVERTED_FLIGHT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GRIPPER function payload_fns.payload_75_cmd211(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19448,36 +22385,49 @@ function payload_fns.payload_75_cmd211(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_AUTOTUNE_ENABLE function payload_fns.payload_75_cmd212(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19485,36 +22435,50 @@ function payload_fns.payload_75_cmd212(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2, tvbrange, value) + dissect_flags_AUTOTUNE_AXIS(subtree, "cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_SET_YAW_SPEED function payload_fns.payload_75_cmd213(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19522,36 +22486,49 @@ function payload_fns.payload_75_cmd213(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL function payload_fns.payload_75_cmd214(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19559,36 +22536,49 @@ function payload_fns.payload_75_cmd214(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_RESUME_REPEAT_DIST function payload_fns.payload_75_cmd215(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19596,36 +22586,49 @@ function payload_fns.payload_75_cmd215(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_RESUME_REPEAT_DIST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RESUME_REPEAT_DIST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SPRAYER function payload_fns.payload_75_cmd216(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19633,36 +22636,49 @@ function payload_fns.payload_75_cmd216(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SPRAYER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SPRAYER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SEND_SCRIPT_MESSAGE function payload_fns.payload_75_cmd217(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19670,36 +22686,49 @@ function payload_fns.payload_75_cmd217(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_AUX_FUNCTION function payload_fns.payload_75_cmd218(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19707,36 +22736,49 @@ function payload_fns.payload_75_cmd218(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_MOUNT_CONTROL_QUAT function payload_fns.payload_75_cmd220(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19744,36 +22786,49 @@ function payload_fns.payload_75_cmd220(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GUIDED_MASTER function payload_fns.payload_75_cmd221(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19781,36 +22836,49 @@ function payload_fns.payload_75_cmd221(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GUIDED_LIMITS function payload_fns.payload_75_cmd222(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19818,36 +22886,49 @@ function payload_fns.payload_75_cmd222(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_ENGINE_CONTROL function payload_fns.payload_75_cmd223(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19855,36 +22936,49 @@ function payload_fns.payload_75_cmd223(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SET_MISSION_CURRENT function payload_fns.payload_75_cmd224(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19892,36 +22986,49 @@ function payload_fns.payload_75_cmd224(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_LAST function payload_fns.payload_75_cmd240(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19929,36 +23036,49 @@ function payload_fns.payload_75_cmd240(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PREFLIGHT_CALIBRATION function payload_fns.payload_75_cmd241(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -19966,36 +23086,49 @@ function payload_fns.payload_75_cmd241(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS function payload_fns.payload_75_cmd242(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20003,36 +23136,49 @@ function payload_fns.payload_75_cmd242(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PREFLIGHT_UAVCAN function payload_fns.payload_75_cmd243(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20040,36 +23186,49 @@ function payload_fns.payload_75_cmd243(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_UAVCAN_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_UAVCAN_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PREFLIGHT_STORAGE function payload_fns.payload_75_cmd245(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20077,36 +23236,49 @@ function payload_fns.payload_75_cmd245(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN function payload_fns.payload_75_cmd246(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20114,36 +23286,49 @@ function payload_fns.payload_75_cmd246(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_OVERRIDE_GOTO function payload_fns.payload_75_cmd252(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20151,36 +23336,49 @@ function payload_fns.payload_75_cmd252(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_OBLIQUE_SURVEY function payload_fns.payload_75_cmd260(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20188,36 +23386,49 @@ function payload_fns.payload_75_cmd260(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_MISSION_START function payload_fns.payload_75_cmd300(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20225,36 +23436,49 @@ function payload_fns.payload_75_cmd300(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_COMPONENT_ARM_DISARM function payload_fns.payload_75_cmd400(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20262,36 +23486,49 @@ function payload_fns.payload_75_cmd400(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_RUN_PREARM_CHECKS function payload_fns.payload_75_cmd401(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20299,36 +23536,49 @@ function payload_fns.payload_75_cmd401(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GET_HOME_POSITION function payload_fns.payload_75_cmd410(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20336,36 +23586,49 @@ function payload_fns.payload_75_cmd410(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_START_RX_PAIR function payload_fns.payload_75_cmd500(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20373,36 +23636,49 @@ function payload_fns.payload_75_cmd500(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GET_MESSAGE_INTERVAL function payload_fns.payload_75_cmd510(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20410,36 +23686,49 @@ function payload_fns.payload_75_cmd510(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GET_MESSAGE_INTERVAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GET_MESSAGE_INTERVAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_MESSAGE_INTERVAL function payload_fns.payload_75_cmd511(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20447,36 +23736,49 @@ function payload_fns.payload_75_cmd511(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_MESSAGE function payload_fns.payload_75_cmd512(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20484,36 +23786,49 @@ function payload_fns.payload_75_cmd512(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_PROTOCOL_VERSION function payload_fns.payload_75_cmd519(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20521,36 +23836,49 @@ function payload_fns.payload_75_cmd519(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_PROTOCOL_VERSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_PROTOCOL_VERSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES function payload_fns.payload_75_cmd520(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20558,36 +23886,49 @@ function payload_fns.payload_75_cmd520(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_CAMERA_INFORMATION function payload_fns.payload_75_cmd521(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20595,36 +23936,49 @@ function payload_fns.payload_75_cmd521(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_CAMERA_SETTINGS function payload_fns.payload_75_cmd522(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20632,36 +23986,49 @@ function payload_fns.payload_75_cmd522(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_SETTINGS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_SETTINGS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_STORAGE_INFORMATION function payload_fns.payload_75_cmd525(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20669,36 +24036,49 @@ function payload_fns.payload_75_cmd525(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_STORAGE_FORMAT function payload_fns.payload_75_cmd526(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20706,36 +24086,49 @@ function payload_fns.payload_75_cmd526(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS function payload_fns.payload_75_cmd527(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20743,36 +24136,49 @@ function payload_fns.payload_75_cmd527(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_FLIGHT_INFORMATION function payload_fns.payload_75_cmd528(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20780,36 +24186,49 @@ function payload_fns.payload_75_cmd528(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_FLIGHT_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_FLIGHT_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_RESET_CAMERA_SETTINGS function payload_fns.payload_75_cmd529(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20817,36 +24236,49 @@ function payload_fns.payload_75_cmd529(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_RESET_CAMERA_SETTINGS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_RESET_CAMERA_SETTINGS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_CAMERA_MODE function payload_fns.payload_75_cmd530(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20854,36 +24286,49 @@ function payload_fns.payload_75_cmd530(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_MODE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_MODE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_CAMERA_ZOOM function payload_fns.payload_75_cmd531(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20891,36 +24336,49 @@ function payload_fns.payload_75_cmd531(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_CAMERA_FOCUS function payload_fns.payload_75_cmd532(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20928,36 +24386,49 @@ function payload_fns.payload_75_cmd532(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_JUMP_TAG function payload_fns.payload_75_cmd600(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -20965,36 +24436,49 @@ function payload_fns.payload_75_cmd600(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_JUMP_TAG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_JUMP_TAG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_JUMP_TAG function payload_fns.payload_75_cmd601(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21002,36 +24486,49 @@ function payload_fns.payload_75_cmd601(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW function payload_fns.payload_75_cmd1000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21039,37 +24536,100 @@ function payload_fns.payload_75_cmd1000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5, padded(field_offset, 4)) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", value) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE +function payload_fns.payload_75_cmd1001(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 35 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 35) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_IMAGE_START_CAPTURE function payload_fns.payload_75_cmd2000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21077,36 +24637,49 @@ function payload_fns.payload_75_cmd2000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_IMAGE_STOP_CAPTURE function payload_fns.payload_75_cmd2001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21114,36 +24687,49 @@ function payload_fns.payload_75_cmd2001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_TRIGGER_CONTROL function payload_fns.payload_75_cmd2003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21151,36 +24737,49 @@ function payload_fns.payload_75_cmd2003(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CAMERA_TRACK_POINT function payload_fns.payload_75_cmd2004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21188,36 +24787,49 @@ function payload_fns.payload_75_cmd2004(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CAMERA_TRACK_RECTANGLE function payload_fns.payload_75_cmd2005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21225,36 +24837,49 @@ function payload_fns.payload_75_cmd2005(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CAMERA_STOP_TRACKING function payload_fns.payload_75_cmd2010(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21262,36 +24887,49 @@ function payload_fns.payload_75_cmd2010(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_VIDEO_START_CAPTURE function payload_fns.payload_75_cmd2500(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21299,36 +24937,49 @@ function payload_fns.payload_75_cmd2500(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_VIDEO_STOP_CAPTURE function payload_fns.payload_75_cmd2501(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21336,36 +24987,49 @@ function payload_fns.payload_75_cmd2501(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_CAPTURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_CAPTURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_VIDEO_START_STREAMING function payload_fns.payload_75_cmd2502(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21373,36 +25037,49 @@ function payload_fns.payload_75_cmd2502(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_STREAMING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_STREAMING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_VIDEO_STOP_STREAMING function payload_fns.payload_75_cmd2503(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21410,36 +25087,49 @@ function payload_fns.payload_75_cmd2503(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_STREAMING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_STREAMING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION function payload_fns.payload_75_cmd2504(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21447,36 +25137,49 @@ function payload_fns.payload_75_cmd2504(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_REQUEST_VIDEO_STREAM_STATUS function payload_fns.payload_75_cmd2505(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21484,36 +25187,49 @@ function payload_fns.payload_75_cmd2505(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_STATUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_LOGGING_START function payload_fns.payload_75_cmd2510(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21521,36 +25237,49 @@ function payload_fns.payload_75_cmd2510(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_LOGGING_START_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_LOGGING_START_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_LOGGING_STOP function payload_fns.payload_75_cmd2511(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21558,36 +25287,49 @@ function payload_fns.payload_75_cmd2511(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_AIRFRAME_CONFIGURATION function payload_fns.payload_75_cmd2520(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21595,36 +25337,49 @@ function payload_fns.payload_75_cmd2520(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CONTROL_HIGH_LATENCY function payload_fns.payload_75_cmd2600(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21632,36 +25387,49 @@ function payload_fns.payload_75_cmd2600(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONTROL_HIGH_LATENCY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONTROL_HIGH_LATENCY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PANORAMA_CREATE function payload_fns.payload_75_cmd2800(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21669,36 +25437,49 @@ function payload_fns.payload_75_cmd2800(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_VTOL_TRANSITION function payload_fns.payload_75_cmd3000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21706,36 +25487,49 @@ function payload_fns.payload_75_cmd3000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_VTOL_TRANSITION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_VTOL_TRANSITION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_ARM_AUTHORIZATION_REQUEST function payload_fns.payload_75_cmd3001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21743,36 +25537,49 @@ function payload_fns.payload_75_cmd3001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_ARM_AUTHORIZATION_REQUEST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_ARM_AUTHORIZATION_REQUEST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_GUIDED_SUBMODE_STANDARD function payload_fns.payload_75_cmd4000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21780,36 +25587,49 @@ function payload_fns.payload_75_cmd4000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE function payload_fns.payload_75_cmd4001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21817,36 +25637,49 @@ function payload_fns.payload_75_cmd4001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_FENCE_RETURN_POINT function payload_fns.payload_75_cmd5000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21854,36 +25687,49 @@ function payload_fns.payload_75_cmd5000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION function payload_fns.payload_75_cmd5001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21891,36 +25737,49 @@ function payload_fns.payload_75_cmd5001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION function payload_fns.payload_75_cmd5002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21928,36 +25787,49 @@ function payload_fns.payload_75_cmd5002(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION function payload_fns.payload_75_cmd5003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -21965,36 +25837,49 @@ function payload_fns.payload_75_cmd5003(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION function payload_fns.payload_75_cmd5004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22002,36 +25887,49 @@ function payload_fns.payload_75_cmd5004(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_RALLY_POINT function payload_fns.payload_75_cmd5100(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22039,36 +25937,49 @@ function payload_fns.payload_75_cmd5100(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_UAVCAN_GET_NODE_INFO function payload_fns.payload_75_cmd5200(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22076,36 +25987,49 @@ function payload_fns.payload_75_cmd5200(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_ADSB_OUT_IDENT function payload_fns.payload_75_cmd10001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22113,36 +26037,49 @@ function payload_fns.payload_75_cmd10001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_LOWEHEISER_SET_STATE function payload_fns.payload_75_cmd10151(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22150,36 +26087,49 @@ function payload_fns.payload_75_cmd10151(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PAYLOAD_PREPARE_DEPLOY function payload_fns.payload_75_cmd30001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22187,36 +26137,49 @@ function payload_fns.payload_75_cmd30001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_PAYLOAD_CONTROL_DEPLOY function payload_fns.payload_75_cmd30002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22224,36 +26187,49 @@ function payload_fns.payload_75_cmd30002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_CONTROL_DEPLOY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_CONTROL_DEPLOY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_WAYPOINT_USER_1 function payload_fns.payload_75_cmd31000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22261,36 +26237,49 @@ function payload_fns.payload_75_cmd31000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_WAYPOINT_USER_2 function payload_fns.payload_75_cmd31001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22298,36 +26287,49 @@ function payload_fns.payload_75_cmd31001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_WAYPOINT_USER_3 function payload_fns.payload_75_cmd31002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22335,36 +26337,49 @@ function payload_fns.payload_75_cmd31002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_WAYPOINT_USER_4 function payload_fns.payload_75_cmd31003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22372,36 +26387,49 @@ function payload_fns.payload_75_cmd31003(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_WAYPOINT_USER_5 function payload_fns.payload_75_cmd31004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22409,36 +26437,49 @@ function payload_fns.payload_75_cmd31004(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SPATIAL_USER_1 function payload_fns.payload_75_cmd31005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22446,36 +26487,49 @@ function payload_fns.payload_75_cmd31005(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SPATIAL_USER_2 function payload_fns.payload_75_cmd31006(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22483,36 +26537,49 @@ function payload_fns.payload_75_cmd31006(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SPATIAL_USER_3 function payload_fns.payload_75_cmd31007(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22520,36 +26587,49 @@ function payload_fns.payload_75_cmd31007(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SPATIAL_USER_4 function payload_fns.payload_75_cmd31008(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22557,36 +26637,49 @@ function payload_fns.payload_75_cmd31008(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SPATIAL_USER_5 function payload_fns.payload_75_cmd31009(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22594,36 +26687,49 @@ function payload_fns.payload_75_cmd31009(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_USER_1 function payload_fns.payload_75_cmd31010(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22631,36 +26737,49 @@ function payload_fns.payload_75_cmd31010(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_USER_2 function payload_fns.payload_75_cmd31011(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22668,36 +26787,49 @@ function payload_fns.payload_75_cmd31011(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_USER_3 function payload_fns.payload_75_cmd31012(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22705,36 +26837,49 @@ function payload_fns.payload_75_cmd31012(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_USER_4 function payload_fns.payload_75_cmd31013(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22742,36 +26887,49 @@ function payload_fns.payload_75_cmd31013(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_USER_5 function payload_fns.payload_75_cmd31014(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22779,36 +26937,49 @@ function payload_fns.payload_75_cmd31014(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_CAN_FORWARD function payload_fns.payload_75_cmd32000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22816,36 +26987,49 @@ function payload_fns.payload_75_cmd32000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAN_FORWARD_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAN_FORWARD_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_POWER_OFF_INITIATED function payload_fns.payload_75_cmd42000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22853,36 +27037,49 @@ function payload_fns.payload_75_cmd42000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_FLY_CLICK function payload_fns.payload_75_cmd42001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22890,36 +27087,49 @@ function payload_fns.payload_75_cmd42001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_FLY_HOLD function payload_fns.payload_75_cmd42002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22927,36 +27137,49 @@ function payload_fns.payload_75_cmd42002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SOLO_BTN_PAUSE_CLICK function payload_fns.payload_75_cmd42003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -22964,36 +27187,49 @@ function payload_fns.payload_75_cmd42003(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL function payload_fns.payload_75_cmd42004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23001,36 +27237,49 @@ function payload_fns.payload_75_cmd42004(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL_FIELD function payload_fns.payload_75_cmd42005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23038,36 +27287,49 @@ function payload_fns.payload_75_cmd42005(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_FIXED_MAG_CAL_YAW function payload_fns.payload_75_cmd42006(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23075,36 +27337,49 @@ function payload_fns.payload_75_cmd42006(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_EKF_SOURCE_SET function payload_fns.payload_75_cmd42007(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23112,36 +27387,49 @@ function payload_fns.payload_75_cmd42007(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_START_MAG_CAL function payload_fns.payload_75_cmd42424(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23149,36 +27437,49 @@ function payload_fns.payload_75_cmd42424(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_ACCEPT_MAG_CAL function payload_fns.payload_75_cmd42425(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23186,36 +27487,49 @@ function payload_fns.payload_75_cmd42425(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_CANCEL_MAG_CAL function payload_fns.payload_75_cmd42426(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23223,36 +27537,49 @@ function payload_fns.payload_75_cmd42426(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SET_FACTORY_TEST_MODE function payload_fns.payload_75_cmd42427(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23260,36 +27587,49 @@ function payload_fns.payload_75_cmd42427(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_SEND_BANNER function payload_fns.payload_75_cmd42428(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23297,36 +27637,49 @@ function payload_fns.payload_75_cmd42428(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_ACCELCAL_VEHICLE_POS function payload_fns.payload_75_cmd42429(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23334,36 +27687,49 @@ function payload_fns.payload_75_cmd42429(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_RESET function payload_fns.payload_75_cmd42501(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23371,36 +27737,49 @@ function payload_fns.payload_75_cmd42501(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS function payload_fns.payload_75_cmd42502(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23408,36 +27787,49 @@ function payload_fns.payload_75_cmd42502(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION function payload_fns.payload_75_cmd42503(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23445,36 +27837,49 @@ function payload_fns.payload_75_cmd42503(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GIMBAL_FULL_RESET function payload_fns.payload_75_cmd42505(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23482,36 +27887,49 @@ function payload_fns.payload_75_cmd42505(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DO_WINCH function payload_fns.payload_75_cmd42600(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23519,36 +27937,49 @@ function payload_fns.payload_75_cmd42600(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_FLASH_BOOTLOADER function payload_fns.payload_75_cmd42650(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23556,36 +27987,49 @@ function payload_fns.payload_75_cmd42650(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_BATTERY_RESET function payload_fns.payload_75_cmd42651(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23593,36 +28037,49 @@ function payload_fns.payload_75_cmd42651(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_DEBUG_TRAP function payload_fns.payload_75_cmd42700(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23630,36 +28087,49 @@ function payload_fns.payload_75_cmd42700(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_SCRIPTING function payload_fns.payload_75_cmd42701(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23667,36 +28137,49 @@ function payload_fns.payload_75_cmd42701(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_SCRIPT_TIME function payload_fns.payload_75_cmd42702(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23704,36 +28187,49 @@ function payload_fns.payload_75_cmd42702(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_NAV_ATTITUDE_TIME function payload_fns.payload_75_cmd42703(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23741,36 +28237,49 @@ function payload_fns.payload_75_cmd42703(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_SPEED function payload_fns.payload_75_cmd43000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23778,36 +28287,49 @@ function payload_fns.payload_75_cmd43000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_ALTITUDE function payload_fns.payload_75_cmd43001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23815,36 +28337,99 @@ function payload_fns.payload_75_cmd43001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_GUIDED_CHANGE_HEADING function payload_fns.payload_75_cmd43002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange + if (offset + 35 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 35) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) +end +-- dissect payload of message type COMMAND_INT with command MAV_CMD_EXTERNAL_POSITION_ESTIMATE +function payload_fns.payload_75_cmd43003(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23852,36 +28437,49 @@ function payload_fns.payload_75_cmd43002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_INT with command MAV_CMD_ENUM_END -function payload_fns.payload_75_cmd43003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree +function payload_fns.payload_75_cmd43004(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23889,36 +28487,49 @@ function payload_fns.payload_75_cmd43003(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_INT function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -23936,36 +28547,49 @@ function payload_fns.payload_75(buffer, tree, msgid, offset, limit, pinfo) cmd_fn(buffer, tree, msgid, offset, limit, pinfo) return end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_INT_frame, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_INT_command, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.COMMAND_INT_current, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.COMMAND_INT_autocontinue, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_INT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_INT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_INT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_INT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_INT_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_INT_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_INT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_frame, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_command, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_current, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_INT_autocontinue, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_INT_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_INT_z, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_WAYPOINT function payload_fns.payload_76_cmd16(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -23973,32 +28597,43 @@ function payload_fns.payload_76_cmd16(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_WAYPOINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_UNLIM function payload_fns.payload_76_cmd17(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24006,32 +28641,43 @@ function payload_fns.payload_76_cmd17(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_UNLIM_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TURNS function payload_fns.payload_76_cmd18(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24039,32 +28685,43 @@ function payload_fns.payload_76_cmd18(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TURNS_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TIME function payload_fns.payload_76_cmd19(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24072,32 +28729,43 @@ function payload_fns.payload_76_cmd19(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TIME_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_RETURN_TO_LAUNCH function payload_fns.payload_76_cmd20(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24105,32 +28773,43 @@ function payload_fns.payload_76_cmd20(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAND function payload_fns.payload_76_cmd21(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24138,32 +28817,43 @@ function payload_fns.payload_76_cmd21(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_TAKEOFF function payload_fns.payload_76_cmd22(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24171,32 +28861,43 @@ function payload_fns.payload_76_cmd22(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAND_LOCAL function payload_fns.payload_76_cmd23(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24204,32 +28905,43 @@ function payload_fns.payload_76_cmd23(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LAND_LOCAL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_TAKEOFF_LOCAL function payload_fns.payload_76_cmd24(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24237,32 +28949,43 @@ function payload_fns.payload_76_cmd24(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_TAKEOFF_LOCAL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FOLLOW function payload_fns.payload_76_cmd25(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24270,32 +28993,43 @@ function payload_fns.payload_76_cmd25(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FOLLOW_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT function payload_fns.payload_76_cmd30(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24303,32 +29037,43 @@ function payload_fns.payload_76_cmd30(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LOITER_TO_ALT function payload_fns.payload_76_cmd31(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24336,32 +29081,43 @@ function payload_fns.payload_76_cmd31(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_LOITER_TO_ALT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FOLLOW function payload_fns.payload_76_cmd32(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24369,32 +29125,43 @@ function payload_fns.payload_76_cmd32(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FOLLOW_REPOSITION function payload_fns.payload_76_cmd33(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24402,32 +29169,43 @@ function payload_fns.payload_76_cmd33(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FOLLOW_REPOSITION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ROI function payload_fns.payload_76_cmd80(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24435,32 +29213,43 @@ function payload_fns.payload_76_cmd80(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ROI_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_PATHPLANNING function payload_fns.payload_76_cmd81(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24468,32 +29257,43 @@ function payload_fns.payload_76_cmd81(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PATHPLANNING_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SPLINE_WAYPOINT function payload_fns.payload_76_cmd82(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24501,32 +29301,43 @@ function payload_fns.payload_76_cmd82(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SPLINE_WAYPOINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ALTITUDE_WAIT function payload_fns.payload_76_cmd83(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24534,32 +29345,43 @@ function payload_fns.payload_76_cmd83(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ALTITUDE_WAIT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_VTOL_TAKEOFF function payload_fns.payload_76_cmd84(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24567,32 +29389,43 @@ function payload_fns.payload_76_cmd84(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_TAKEOFF_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_VTOL_LAND function payload_fns.payload_76_cmd85(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24600,32 +29433,43 @@ function payload_fns.payload_76_cmd85(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_VTOL_LAND_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_GUIDED_ENABLE function payload_fns.payload_76_cmd92(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24633,32 +29477,43 @@ function payload_fns.payload_76_cmd92(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_GUIDED_ENABLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_GUIDED_ENABLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_DELAY function payload_fns.payload_76_cmd93(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24666,32 +29521,43 @@ function payload_fns.payload_76_cmd93(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_DELAY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_PAYLOAD_PLACE function payload_fns.payload_76_cmd94(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24699,32 +29565,43 @@ function payload_fns.payload_76_cmd94(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_PAYLOAD_PLACE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_LAST function payload_fns.payload_76_cmd95(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24732,32 +29609,43 @@ function payload_fns.payload_76_cmd95(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_DELAY function payload_fns.payload_76_cmd112(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24765,32 +29653,43 @@ function payload_fns.payload_76_cmd112(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_DELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_CHANGE_ALT function payload_fns.payload_76_cmd113(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24798,32 +29697,43 @@ function payload_fns.payload_76_cmd113(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_CHANGE_ALT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_DISTANCE function payload_fns.payload_76_cmd114(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24831,32 +29741,43 @@ function payload_fns.payload_76_cmd114(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_DISTANCE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_DISTANCE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_YAW function payload_fns.payload_76_cmd115(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24864,32 +29785,43 @@ function payload_fns.payload_76_cmd115(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONDITION_YAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONDITION_LAST function payload_fns.payload_76_cmd159(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24897,32 +29829,43 @@ function payload_fns.payload_76_cmd159(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_MODE function payload_fns.payload_76_cmd176(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24930,32 +29873,43 @@ function payload_fns.payload_76_cmd176(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MODE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_JUMP function payload_fns.payload_76_cmd177(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24963,32 +29917,43 @@ function payload_fns.payload_76_cmd177(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CHANGE_SPEED function payload_fns.payload_76_cmd178(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -24996,32 +29961,43 @@ function payload_fns.payload_76_cmd178(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_SPEED_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_HOME function payload_fns.payload_76_cmd179(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25029,32 +30005,43 @@ function payload_fns.payload_76_cmd179(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_HOME_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_PARAMETER function payload_fns.payload_76_cmd180(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25062,32 +30049,43 @@ function payload_fns.payload_76_cmd180(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_PARAMETER_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_RELAY function payload_fns.payload_76_cmd181(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25095,32 +30093,43 @@ function payload_fns.payload_76_cmd181(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RELAY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPEAT_RELAY function payload_fns.payload_76_cmd182(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25128,32 +30137,43 @@ function payload_fns.payload_76_cmd182(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_RELAY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_SERVO function payload_fns.payload_76_cmd183(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25161,32 +30181,43 @@ function payload_fns.payload_76_cmd183(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_SERVO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPEAT_SERVO function payload_fns.payload_76_cmd184(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25194,32 +30225,43 @@ function payload_fns.payload_76_cmd184(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPEAT_SERVO_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FLIGHTTERMINATION function payload_fns.payload_76_cmd185(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25227,32 +30269,43 @@ function payload_fns.payload_76_cmd185(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FLIGHTTERMINATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FLIGHTTERMINATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CHANGE_ALTITUDE function payload_fns.payload_76_cmd186(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25260,32 +30313,43 @@ function payload_fns.payload_76_cmd186(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CHANGE_ALTITUDE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_LAND_START function payload_fns.payload_76_cmd189(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25293,32 +30357,43 @@ function payload_fns.payload_76_cmd189(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_LAND_START_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_RALLY_LAND function payload_fns.payload_76_cmd190(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25326,32 +30401,43 @@ function payload_fns.payload_76_cmd190(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_RALLY_LAND_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GO_AROUND function payload_fns.payload_76_cmd191(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25359,32 +30445,43 @@ function payload_fns.payload_76_cmd191(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GO_AROUND_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GO_AROUND_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_REPOSITION function payload_fns.payload_76_cmd192(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25392,33 +30489,44 @@ function payload_fns.payload_76_cmd192(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param2, padded(field_offset, 4)) - dissect_flags_MAV_DO_REPOSITION_FLAGS(subtree, "cmd_MAV_CMD_DO_REPOSITION_param2", value) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param2, tvbrange, value) + dissect_flags_MAV_DO_REPOSITION_FLAGS(subtree, "cmd_MAV_CMD_DO_REPOSITION_param2", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_REPOSITION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_PAUSE_CONTINUE function payload_fns.payload_76_cmd193(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25426,32 +30534,43 @@ function payload_fns.payload_76_cmd193(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_PAUSE_CONTINUE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_PAUSE_CONTINUE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_REVERSE function payload_fns.payload_76_cmd194(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25459,32 +30578,43 @@ function payload_fns.payload_76_cmd194(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_REVERSE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_REVERSE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_LOCATION function payload_fns.payload_76_cmd195(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25492,32 +30622,43 @@ function payload_fns.payload_76_cmd195(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_LOCATION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET function payload_fns.payload_76_cmd196(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25525,32 +30666,43 @@ function payload_fns.payload_76_cmd196(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_NONE function payload_fns.payload_76_cmd197(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25558,32 +30710,43 @@ function payload_fns.payload_76_cmd197(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI_SYSID function payload_fns.payload_76_cmd198(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25591,32 +30754,43 @@ function payload_fns.payload_76_cmd198(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_SYSID_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_SYSID_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CONTROL_VIDEO function payload_fns.payload_76_cmd200(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25624,32 +30798,43 @@ function payload_fns.payload_76_cmd200(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CONTROL_VIDEO_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_ROI function payload_fns.payload_76_cmd201(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25657,32 +30842,43 @@ function payload_fns.payload_76_cmd201(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_ROI_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_DIGICAM_CONFIGURE function payload_fns.payload_76_cmd202(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25690,32 +30886,43 @@ function payload_fns.payload_76_cmd202(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONFIGURE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_DIGICAM_CONTROL function payload_fns.payload_76_cmd203(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25723,32 +30930,43 @@ function payload_fns.payload_76_cmd203(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_DIGICAM_CONTROL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONFIGURE function payload_fns.payload_76_cmd204(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25756,32 +30974,43 @@ function payload_fns.payload_76_cmd204(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONFIGURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONTROL function payload_fns.payload_76_cmd205(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25789,32 +31018,43 @@ function payload_fns.payload_76_cmd205(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_CAM_TRIGG_DIST function payload_fns.payload_76_cmd206(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25822,32 +31062,43 @@ function payload_fns.payload_76_cmd206(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_DIST_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_FENCE_ENABLE function payload_fns.payload_76_cmd207(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25855,32 +31106,43 @@ function payload_fns.payload_76_cmd207(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_FENCE_ENABLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_PARACHUTE function payload_fns.payload_76_cmd208(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25888,32 +31150,43 @@ function payload_fns.payload_76_cmd208(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_PARACHUTE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_PARACHUTE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOTOR_TEST function payload_fns.payload_76_cmd209(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25921,32 +31194,43 @@ function payload_fns.payload_76_cmd209(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOTOR_TEST_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_INVERTED_FLIGHT function payload_fns.payload_76_cmd210(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25954,32 +31238,43 @@ function payload_fns.payload_76_cmd210(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_INVERTED_FLIGHT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_INVERTED_FLIGHT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GRIPPER function payload_fns.payload_76_cmd211(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -25987,32 +31282,43 @@ function payload_fns.payload_76_cmd211(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GRIPPER_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_AUTOTUNE_ENABLE function payload_fns.payload_76_cmd212(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26020,32 +31326,44 @@ function payload_fns.payload_76_cmd212(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2, tvbrange, value) + dissect_flags_AUTOTUNE_AXIS(subtree, "cmd_MAV_CMD_DO_AUTOTUNE_ENABLE_param2", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SET_YAW_SPEED function payload_fns.payload_76_cmd213(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26053,32 +31371,43 @@ function payload_fns.payload_76_cmd213(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SET_YAW_SPEED_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL function payload_fns.payload_76_cmd214(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26086,32 +31415,43 @@ function payload_fns.payload_76_cmd214(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_RESUME_REPEAT_DIST function payload_fns.payload_76_cmd215(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26119,32 +31459,43 @@ function payload_fns.payload_76_cmd215(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_RESUME_REPEAT_DIST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_RESUME_REPEAT_DIST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SPRAYER function payload_fns.payload_76_cmd216(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26152,32 +31503,43 @@ function payload_fns.payload_76_cmd216(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SPRAYER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SPRAYER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SEND_SCRIPT_MESSAGE function payload_fns.payload_76_cmd217(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26185,32 +31547,43 @@ function payload_fns.payload_76_cmd217(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SEND_SCRIPT_MESSAGE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_AUX_FUNCTION function payload_fns.payload_76_cmd218(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26218,32 +31591,43 @@ function payload_fns.payload_76_cmd218(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_AUX_FUNCTION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_MOUNT_CONTROL_QUAT function payload_fns.payload_76_cmd220(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26251,32 +31635,43 @@ function payload_fns.payload_76_cmd220(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_MOUNT_CONTROL_QUAT_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GUIDED_MASTER function payload_fns.payload_76_cmd221(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26284,32 +31679,43 @@ function payload_fns.payload_76_cmd221(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_MASTER_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GUIDED_LIMITS function payload_fns.payload_76_cmd222(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26317,32 +31723,43 @@ function payload_fns.payload_76_cmd222(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GUIDED_LIMITS_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ENGINE_CONTROL function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26350,32 +31767,43 @@ function payload_fns.payload_76_cmd223(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ENGINE_CONTROL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SET_MISSION_CURRENT function payload_fns.payload_76_cmd224(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26383,32 +31811,43 @@ function payload_fns.payload_76_cmd224(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_SET_MISSION_CURRENT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_LAST function payload_fns.payload_76_cmd240(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26416,32 +31855,43 @@ function payload_fns.payload_76_cmd240(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_CALIBRATION function payload_fns.payload_76_cmd241(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26449,32 +31899,43 @@ function payload_fns.payload_76_cmd241(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_CALIBRATION_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS function payload_fns.payload_76_cmd242(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26482,32 +31943,43 @@ function payload_fns.payload_76_cmd242(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_UAVCAN function payload_fns.payload_76_cmd243(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26515,32 +31987,43 @@ function payload_fns.payload_76_cmd243(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_UAVCAN_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_UAVCAN_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_STORAGE function payload_fns.payload_76_cmd245(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26548,32 +32031,43 @@ function payload_fns.payload_76_cmd245(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_STORAGE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN function payload_fns.payload_76_cmd246(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26581,32 +32075,43 @@ function payload_fns.payload_76_cmd246(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_OVERRIDE_GOTO function payload_fns.payload_76_cmd252(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26614,32 +32119,43 @@ function payload_fns.payload_76_cmd252(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OVERRIDE_GOTO_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_OBLIQUE_SURVEY function payload_fns.payload_76_cmd260(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26647,32 +32163,43 @@ function payload_fns.payload_76_cmd260(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_OBLIQUE_SURVEY_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_MISSION_START function payload_fns.payload_76_cmd300(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26680,32 +32207,43 @@ function payload_fns.payload_76_cmd300(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_MISSION_START_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_COMPONENT_ARM_DISARM function payload_fns.payload_76_cmd400(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26713,32 +32251,43 @@ function payload_fns.payload_76_cmd400(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_COMPONENT_ARM_DISARM_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_RUN_PREARM_CHECKS function payload_fns.payload_76_cmd401(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26746,32 +32295,43 @@ function payload_fns.payload_76_cmd401(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GET_HOME_POSITION function payload_fns.payload_76_cmd410(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26779,32 +32339,43 @@ function payload_fns.payload_76_cmd410(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_START_RX_PAIR function payload_fns.payload_76_cmd500(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26812,32 +32383,43 @@ function payload_fns.payload_76_cmd500(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_START_RX_PAIR_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GET_MESSAGE_INTERVAL function payload_fns.payload_76_cmd510(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26845,32 +32427,43 @@ function payload_fns.payload_76_cmd510(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GET_MESSAGE_INTERVAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GET_MESSAGE_INTERVAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_MESSAGE_INTERVAL function payload_fns.payload_76_cmd511(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26878,32 +32471,43 @@ function payload_fns.payload_76_cmd511(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_MESSAGE_INTERVAL_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_MESSAGE function payload_fns.payload_76_cmd512(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26911,32 +32515,43 @@ function payload_fns.payload_76_cmd512(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_MESSAGE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_PROTOCOL_VERSION function payload_fns.payload_76_cmd519(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26944,32 +32559,43 @@ function payload_fns.payload_76_cmd519(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_PROTOCOL_VERSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_PROTOCOL_VERSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES function payload_fns.payload_76_cmd520(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -26977,32 +32603,43 @@ function payload_fns.payload_76_cmd520(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_INFORMATION function payload_fns.payload_76_cmd521(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27010,32 +32647,43 @@ function payload_fns.payload_76_cmd521(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_SETTINGS function payload_fns.payload_76_cmd522(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27043,32 +32691,43 @@ function payload_fns.payload_76_cmd522(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_SETTINGS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_SETTINGS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_STORAGE_INFORMATION function payload_fns.payload_76_cmd525(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27076,32 +32735,43 @@ function payload_fns.payload_76_cmd525(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_STORAGE_INFORMATION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_STORAGE_FORMAT function payload_fns.payload_76_cmd526(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27109,32 +32779,43 @@ function payload_fns.payload_76_cmd526(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_STORAGE_FORMAT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS function payload_fns.payload_76_cmd527(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27142,32 +32823,43 @@ function payload_fns.payload_76_cmd527(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_FLIGHT_INFORMATION function payload_fns.payload_76_cmd528(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27175,32 +32867,43 @@ function payload_fns.payload_76_cmd528(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_FLIGHT_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_FLIGHT_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_RESET_CAMERA_SETTINGS function payload_fns.payload_76_cmd529(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27208,32 +32911,43 @@ function payload_fns.payload_76_cmd529(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_RESET_CAMERA_SETTINGS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_RESET_CAMERA_SETTINGS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_MODE function payload_fns.payload_76_cmd530(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27241,32 +32955,43 @@ function payload_fns.payload_76_cmd530(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_MODE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_MODE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_ZOOM function payload_fns.payload_76_cmd531(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27274,32 +32999,43 @@ function payload_fns.payload_76_cmd531(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_ZOOM_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_CAMERA_FOCUS function payload_fns.payload_76_cmd532(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27307,32 +33043,43 @@ function payload_fns.payload_76_cmd532(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_CAMERA_FOCUS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_JUMP_TAG function payload_fns.payload_76_cmd600(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27340,32 +33087,43 @@ function payload_fns.payload_76_cmd600(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_JUMP_TAG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_JUMP_TAG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_JUMP_TAG function payload_fns.payload_76_cmd601(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27373,32 +33131,88 @@ function payload_fns.payload_76_cmd601(buffer, tree, msgid, offset, limit, pinfo else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_JUMP_TAG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW function payload_fns.payload_76_cmd1000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE +function payload_fns.payload_76_cmd1001(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27406,33 +33220,43 @@ function payload_fns.payload_76_cmd1000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5, padded(field_offset, 4)) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5", value) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_IMAGE_START_CAPTURE function payload_fns.payload_76_cmd2000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27440,32 +33264,43 @@ function payload_fns.payload_76_cmd2000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_IMAGE_START_CAPTURE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_IMAGE_STOP_CAPTURE function payload_fns.payload_76_cmd2001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27473,32 +33308,43 @@ function payload_fns.payload_76_cmd2001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_TRIGGER_CONTROL function payload_fns.payload_76_cmd2003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27506,32 +33352,43 @@ function payload_fns.payload_76_cmd2003(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_TRIGGER_CONTROL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_TRACK_POINT function payload_fns.payload_76_cmd2004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27539,32 +33396,43 @@ function payload_fns.payload_76_cmd2004(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_POINT_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_TRACK_RECTANGLE function payload_fns.payload_76_cmd2005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27572,32 +33440,43 @@ function payload_fns.payload_76_cmd2005(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAMERA_TRACK_RECTANGLE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAMERA_STOP_TRACKING function payload_fns.payload_76_cmd2010(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27605,32 +33484,43 @@ function payload_fns.payload_76_cmd2010(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_START_CAPTURE function payload_fns.payload_76_cmd2500(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27638,32 +33528,43 @@ function payload_fns.payload_76_cmd2500(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_CAPTURE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_STOP_CAPTURE function payload_fns.payload_76_cmd2501(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27671,32 +33572,43 @@ function payload_fns.payload_76_cmd2501(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_CAPTURE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_CAPTURE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_START_STREAMING function payload_fns.payload_76_cmd2502(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27704,32 +33616,43 @@ function payload_fns.payload_76_cmd2502(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_STREAMING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_START_STREAMING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_VIDEO_STOP_STREAMING function payload_fns.payload_76_cmd2503(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27737,32 +33660,43 @@ function payload_fns.payload_76_cmd2503(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_STREAMING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_VIDEO_STOP_STREAMING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION function payload_fns.payload_76_cmd2504(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27770,32 +33704,43 @@ function payload_fns.payload_76_cmd2504(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_REQUEST_VIDEO_STREAM_STATUS function payload_fns.payload_76_cmd2505(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27803,32 +33748,43 @@ function payload_fns.payload_76_cmd2505(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_STATUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_REQUEST_VIDEO_STREAM_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOGGING_START function payload_fns.payload_76_cmd2510(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27836,32 +33792,43 @@ function payload_fns.payload_76_cmd2510(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_LOGGING_START_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_LOGGING_START_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOGGING_STOP function payload_fns.payload_76_cmd2511(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27869,32 +33836,43 @@ function payload_fns.payload_76_cmd2511(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_AIRFRAME_CONFIGURATION function payload_fns.payload_76_cmd2520(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27902,32 +33880,43 @@ function payload_fns.payload_76_cmd2520(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_AIRFRAME_CONFIGURATION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CONTROL_HIGH_LATENCY function payload_fns.payload_76_cmd2600(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27935,32 +33924,43 @@ function payload_fns.payload_76_cmd2600(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CONTROL_HIGH_LATENCY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CONTROL_HIGH_LATENCY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PANORAMA_CREATE function payload_fns.payload_76_cmd2800(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -27968,32 +33968,43 @@ function payload_fns.payload_76_cmd2800(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PANORAMA_CREATE_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_VTOL_TRANSITION function payload_fns.payload_76_cmd3000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28001,32 +34012,43 @@ function payload_fns.payload_76_cmd3000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_VTOL_TRANSITION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_VTOL_TRANSITION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_ARM_AUTHORIZATION_REQUEST function payload_fns.payload_76_cmd3001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28034,32 +34056,43 @@ function payload_fns.payload_76_cmd3001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_ARM_AUTHORIZATION_REQUEST_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_ARM_AUTHORIZATION_REQUEST_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_GUIDED_SUBMODE_STANDARD function payload_fns.payload_76_cmd4000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28067,32 +34100,43 @@ function payload_fns.payload_76_cmd4000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE function payload_fns.payload_76_cmd4001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28100,32 +34144,43 @@ function payload_fns.payload_76_cmd4001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_RETURN_POINT function payload_fns.payload_76_cmd5000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28133,32 +34188,43 @@ function payload_fns.payload_76_cmd5000(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_RETURN_POINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION function payload_fns.payload_76_cmd5001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28166,32 +34232,43 @@ function payload_fns.payload_76_cmd5001(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION function payload_fns.payload_76_cmd5002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28199,32 +34276,43 @@ function payload_fns.payload_76_cmd5002(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION function payload_fns.payload_76_cmd5003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28232,32 +34320,43 @@ function payload_fns.payload_76_cmd5003(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION function payload_fns.payload_76_cmd5004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28265,32 +34364,43 @@ function payload_fns.payload_76_cmd5004(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_RALLY_POINT function payload_fns.payload_76_cmd5100(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28298,32 +34408,43 @@ function payload_fns.payload_76_cmd5100(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_RALLY_POINT_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_UAVCAN_GET_NODE_INFO function payload_fns.payload_76_cmd5200(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28331,32 +34452,43 @@ function payload_fns.payload_76_cmd5200(buffer, tree, msgid, offset, limit, pinf else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ADSB_OUT_IDENT function payload_fns.payload_76_cmd10001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28364,32 +34496,43 @@ function payload_fns.payload_76_cmd10001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_LOWEHEISER_SET_STATE function payload_fns.payload_76_cmd10151(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28397,32 +34540,43 @@ function payload_fns.payload_76_cmd10151(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_PREPARE_DEPLOY function payload_fns.payload_76_cmd30001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28430,32 +34584,43 @@ function payload_fns.payload_76_cmd30001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_PREPARE_DEPLOY_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_PAYLOAD_CONTROL_DEPLOY function payload_fns.payload_76_cmd30002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28463,32 +34628,43 @@ function payload_fns.payload_76_cmd30002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_CONTROL_DEPLOY_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_PAYLOAD_CONTROL_DEPLOY_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_1 function payload_fns.payload_76_cmd31000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28496,32 +34672,43 @@ function payload_fns.payload_76_cmd31000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_1_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_2 function payload_fns.payload_76_cmd31001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28529,32 +34716,43 @@ function payload_fns.payload_76_cmd31001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_2_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_3 function payload_fns.payload_76_cmd31002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28562,32 +34760,43 @@ function payload_fns.payload_76_cmd31002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_3_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_4 function payload_fns.payload_76_cmd31003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28595,32 +34804,43 @@ function payload_fns.payload_76_cmd31003(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_4_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_WAYPOINT_USER_5 function payload_fns.payload_76_cmd31004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28628,32 +34848,43 @@ function payload_fns.payload_76_cmd31004(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_WAYPOINT_USER_5_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_1 function payload_fns.payload_76_cmd31005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28661,32 +34892,43 @@ function payload_fns.payload_76_cmd31005(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_1_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_2 function payload_fns.payload_76_cmd31006(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28694,32 +34936,43 @@ function payload_fns.payload_76_cmd31006(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_2_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_3 function payload_fns.payload_76_cmd31007(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28727,32 +34980,43 @@ function payload_fns.payload_76_cmd31007(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_3_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_4 function payload_fns.payload_76_cmd31008(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28760,32 +35024,43 @@ function payload_fns.payload_76_cmd31008(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_4_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SPATIAL_USER_5 function payload_fns.payload_76_cmd31009(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28793,32 +35068,43 @@ function payload_fns.payload_76_cmd31009(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SPATIAL_USER_5_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_1 function payload_fns.payload_76_cmd31010(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28826,32 +35112,43 @@ function payload_fns.payload_76_cmd31010(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_2 function payload_fns.payload_76_cmd31011(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28859,32 +35156,43 @@ function payload_fns.payload_76_cmd31011(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_3 function payload_fns.payload_76_cmd31012(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28892,32 +35200,43 @@ function payload_fns.payload_76_cmd31012(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_4 function payload_fns.payload_76_cmd31013(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28925,32 +35244,43 @@ function payload_fns.payload_76_cmd31013(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_USER_5 function payload_fns.payload_76_cmd31014(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28958,32 +35288,43 @@ function payload_fns.payload_76_cmd31014(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_CAN_FORWARD function payload_fns.payload_76_cmd32000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -28991,32 +35332,43 @@ function payload_fns.payload_76_cmd32000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_CAN_FORWARD_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_CAN_FORWARD_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_POWER_OFF_INITIATED function payload_fns.payload_76_cmd42000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29024,32 +35376,43 @@ function payload_fns.payload_76_cmd42000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_FLY_CLICK function payload_fns.payload_76_cmd42001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29057,32 +35420,43 @@ function payload_fns.payload_76_cmd42001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_FLY_HOLD function payload_fns.payload_76_cmd42002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29090,32 +35464,43 @@ function payload_fns.payload_76_cmd42002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_FLY_HOLD_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SOLO_BTN_PAUSE_CLICK function payload_fns.payload_76_cmd42003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29123,32 +35508,43 @@ function payload_fns.payload_76_cmd42003(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SOLO_BTN_PAUSE_CLICK_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL function payload_fns.payload_76_cmd42004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29156,32 +35552,43 @@ function payload_fns.payload_76_cmd42004(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL_FIELD function payload_fns.payload_76_cmd42005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29189,32 +35596,43 @@ function payload_fns.payload_76_cmd42005(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_FIELD_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_FIXED_MAG_CAL_YAW function payload_fns.payload_76_cmd42006(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29222,32 +35640,43 @@ function payload_fns.payload_76_cmd42006(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FIXED_MAG_CAL_YAW_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_EKF_SOURCE_SET function payload_fns.payload_76_cmd42007(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29255,32 +35684,43 @@ function payload_fns.payload_76_cmd42007(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_EKF_SOURCE_SET_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_START_MAG_CAL function payload_fns.payload_76_cmd42424(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29288,32 +35728,43 @@ function payload_fns.payload_76_cmd42424(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_START_MAG_CAL_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_ACCEPT_MAG_CAL function payload_fns.payload_76_cmd42425(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29321,32 +35772,43 @@ function payload_fns.payload_76_cmd42425(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_ACCEPT_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_CANCEL_MAG_CAL function payload_fns.payload_76_cmd42426(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29354,32 +35816,43 @@ function payload_fns.payload_76_cmd42426(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_CANCEL_MAG_CAL_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SET_FACTORY_TEST_MODE function payload_fns.payload_76_cmd42427(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29387,32 +35860,43 @@ function payload_fns.payload_76_cmd42427(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_SET_FACTORY_TEST_MODE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_SEND_BANNER function payload_fns.payload_76_cmd42428(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29420,32 +35904,43 @@ function payload_fns.payload_76_cmd42428(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_ACCELCAL_VEHICLE_POS function payload_fns.payload_76_cmd42429(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29453,32 +35948,43 @@ function payload_fns.payload_76_cmd42429(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_ACCELCAL_VEHICLE_POS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_RESET function payload_fns.payload_76_cmd42501(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29486,32 +35992,43 @@ function payload_fns.payload_76_cmd42501(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS function payload_fns.payload_76_cmd42502(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29519,32 +36036,43 @@ function payload_fns.payload_76_cmd42502(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION function payload_fns.payload_76_cmd42503(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29552,32 +36080,43 @@ function payload_fns.payload_76_cmd42503(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GIMBAL_FULL_RESET function payload_fns.payload_76_cmd42505(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29585,32 +36124,43 @@ function payload_fns.payload_76_cmd42505(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DO_WINCH function payload_fns.payload_76_cmd42600(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29618,32 +36168,43 @@ function payload_fns.payload_76_cmd42600(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_DO_WINCH_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_FLASH_BOOTLOADER function payload_fns.payload_76_cmd42650(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29651,32 +36212,43 @@ function payload_fns.payload_76_cmd42650(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_FLASH_BOOTLOADER_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_BATTERY_RESET function payload_fns.payload_76_cmd42651(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29684,32 +36256,43 @@ function payload_fns.payload_76_cmd42651(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_BATTERY_RESET_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_DEBUG_TRAP function payload_fns.payload_76_cmd42700(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29717,32 +36300,43 @@ function payload_fns.payload_76_cmd42700(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_SCRIPTING function payload_fns.payload_76_cmd42701(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29750,32 +36344,43 @@ function payload_fns.payload_76_cmd42701(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_SCRIPT_TIME function payload_fns.payload_76_cmd42702(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29783,32 +36388,43 @@ function payload_fns.payload_76_cmd42702(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_SCRIPT_TIME_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_NAV_ATTITUDE_TIME function payload_fns.payload_76_cmd42703(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29816,32 +36432,43 @@ function payload_fns.payload_76_cmd42703(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_NAV_ATTITUDE_TIME_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_SPEED function payload_fns.payload_76_cmd43000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29849,32 +36476,43 @@ function payload_fns.payload_76_cmd43000(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_SPEED_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_ALTITUDE function payload_fns.payload_76_cmd43001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29882,32 +36520,87 @@ function payload_fns.payload_76_cmd43001(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_ALTITUDE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_GUIDED_CHANGE_HEADING function payload_fns.payload_76_cmd43002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) +end +-- dissect payload of message type COMMAND_LONG with command MAV_CMD_EXTERNAL_POSITION_ESTIMATE +function payload_fns.payload_76_cmd43003(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29915,32 +36608,43 @@ function payload_fns.payload_76_cmd43002(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.cmd_MAV_CMD_GUIDED_CHANGE_HEADING_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG with command MAV_CMD_ENUM_END -function payload_fns.payload_76_cmd43003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree +function payload_fns.payload_76_cmd43004(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29948,32 +36652,43 @@ function payload_fns.payload_76_cmd43003(buffer, tree, msgid, offset, limit, pin else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_LONG function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -29991,32 +36706,43 @@ function payload_fns.payload_76(buffer, tree, msgid, offset, limit, pinfo) cmd_fn(buffer, tree, msgid, offset, limit, pinfo) return end - field_offset = offset + 30 - subtree, value = tree:add_le(f.COMMAND_LONG_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.COMMAND_LONG_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.COMMAND_LONG_command, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.COMMAND_LONG_confirmation, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_LONG_param1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_LONG_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_LONG_param3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COMMAND_LONG_param4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.COMMAND_LONG_param5, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.COMMAND_LONG_param6, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.COMMAND_LONG_param7, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_command, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_LONG_confirmation, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param5, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param6, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COMMAND_LONG_param7, tvbrange, value) end -- dissect payload of message type COMMAND_ACK function payload_fns.payload_77(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 10 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 10) @@ -30029,22 +36755,28 @@ function payload_fns.payload_77(buffer, tree, msgid, offset, limit, pinfo) if cmd_name ~= nil then pinfo.cols.info:append(": " .. cmd_name) end - field_offset = offset + 0 - subtree, value = tree:add_le(f.COMMAND_ACK_command, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.COMMAND_ACK_result, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.COMMAND_ACK_progress, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COMMAND_ACK_result_param2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COMMAND_ACK_target_system, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.COMMAND_ACK_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_command, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_result, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_progress, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.COMMAND_ACK_result_param2, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COMMAND_ACK_target_component, tvbrange, value) end -- dissect payload of message type MANUAL_SETPOINT function payload_fns.payload_81(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 22 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 22) @@ -30052,24 +36784,31 @@ function payload_fns.payload_81(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_roll, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_pitch, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_yaw, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_thrust, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_mode_switch, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.MANUAL_SETPOINT_manual_override_switch, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_SETPOINT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_roll, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_pitch, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_yaw, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MANUAL_SETPOINT_thrust, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_SETPOINT_mode_switch, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MANUAL_SETPOINT_manual_override_switch, tvbrange, value) end -- dissect payload of message type SET_ATTITUDE_TARGET function payload_fns.payload_82(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 39 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 39) @@ -30077,35 +36816,47 @@ function payload_fns.payload_82(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_target_system, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_target_component, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_type_mask, padded(field_offset, 1)) - dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "SET_ATTITUDE_TARGET_type_mask", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_q_0, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_q_1, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_q_2, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_q_3, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_body_roll_rate, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_body_pitch_rate, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_body_yaw_rate, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SET_ATTITUDE_TARGET_thrust, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_target_system, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_target_component, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_type_mask, tvbrange, value) + dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "SET_ATTITUDE_TARGET_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_roll_rate, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_body_yaw_rate, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ATTITUDE_TARGET_thrust, tvbrange, value) end -- dissect payload of message type ATTITUDE_TARGET function payload_fns.payload_83(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 37 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 37) @@ -30113,31 +36864,41 @@ function payload_fns.payload_83(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_type_mask, padded(field_offset, 1)) - dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "ATTITUDE_TARGET_type_mask", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_q_0, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_q_1, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_q_2, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_q_3, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_body_roll_rate, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_body_pitch_rate, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_body_yaw_rate, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ATTITUDE_TARGET_thrust, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ATTITUDE_TARGET_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ATTITUDE_TARGET_type_mask, tvbrange, value) + dissect_flags_ATTITUDE_TARGET_TYPEMASK(subtree, "ATTITUDE_TARGET_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_body_roll_rate, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_body_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_body_yaw_rate, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATTITUDE_TARGET_thrust, tvbrange, value) end -- dissect payload of message type SET_POSITION_TARGET_LOCAL_NED function payload_fns.payload_84(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 53 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 53) @@ -30145,43 +36906,59 @@ function payload_fns.payload_84(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_system, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_component, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_coordinate_frame, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_type_mask, padded(field_offset, 2)) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_LOCAL_NED_type_mask", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vx, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vz, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afx, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afz, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw_rate, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_system, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_target_component, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_LOCAL_NED_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_LOCAL_NED_yaw_rate, tvbrange, value) end -- dissect payload of message type POSITION_TARGET_LOCAL_NED function payload_fns.payload_85(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 51 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 51) @@ -30189,39 +36966,53 @@ function payload_fns.payload_85(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_coordinate_frame, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_type_mask, padded(field_offset, 2)) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_LOCAL_NED_type_mask", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vx, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vz, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afx, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afz, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw_rate, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_LOCAL_NED_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_LOCAL_NED_yaw_rate, tvbrange, value) end -- dissect payload of message type SET_POSITION_TARGET_GLOBAL_INT function payload_fns.payload_86(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 53 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 53) @@ -30229,43 +37020,59 @@ function payload_fns.payload_86(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_system, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_component, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_coordinate_frame, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_type_mask, padded(field_offset, 2)) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_GLOBAL_INT_type_mask", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lat_int, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lon_int, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_alt, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vx, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vz, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afx, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afz, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw_rate, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_system, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_target_component, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "SET_POSITION_TARGET_GLOBAL_INT_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lat_int, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_lon_int, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_POSITION_TARGET_GLOBAL_INT_yaw_rate, tvbrange, value) end -- dissect payload of message type POSITION_TARGET_GLOBAL_INT function payload_fns.payload_87(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 51 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 51) @@ -30273,39 +37080,53 @@ function payload_fns.payload_87(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_coordinate_frame, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_type_mask, padded(field_offset, 2)) - dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_GLOBAL_INT_type_mask", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lat_int, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lon_int, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_alt, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vx, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vz, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afx, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afz, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw_rate, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_coordinate_frame, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_type_mask, tvbrange, value) + dissect_flags_POSITION_TARGET_TYPEMASK(subtree, "POSITION_TARGET_GLOBAL_INT_type_mask", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lat_int, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_lon_int, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_alt, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vx, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_vz, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_afz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.POSITION_TARGET_GLOBAL_INT_yaw_rate, tvbrange, value) end -- dissect payload of message type LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET function payload_fns.payload_89(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -30313,24 +37134,31 @@ function payload_fns.payload_89(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_roll, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_pitch, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_yaw, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_roll, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_pitch, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_yaw, tvbrange, value) end -- dissect payload of message type HIL_STATE function payload_fns.payload_90(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 56 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 56) @@ -30338,42 +37166,58 @@ function payload_fns.payload_90(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_STATE_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_STATE_roll, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_STATE_pitch, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_STATE_yaw, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_STATE_rollspeed, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_STATE_pitchspeed, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_STATE_yawspeed, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_STATE_lat, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_STATE_lon, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIL_STATE_alt, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.HIL_STATE_vx, padded(field_offset, 2)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.HIL_STATE_vy, padded(field_offset, 2)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.HIL_STATE_vz, padded(field_offset, 2)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.HIL_STATE_xacc, padded(field_offset, 2)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.HIL_STATE_yacc, padded(field_offset, 2)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.HIL_STATE_zacc, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_STATE_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_roll, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_pitch, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_yaw, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_rollspeed, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_yawspeed, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_lat, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_lon, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_alt, tvbrange, value) + tvbrange = padded(offset + 44, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_vx, tvbrange, value) + tvbrange = padded(offset + 46, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_vy, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_vz, tvbrange, value) + tvbrange = padded(offset + 50, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_xacc, tvbrange, value) + tvbrange = padded(offset + 52, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_yacc, tvbrange, value) + tvbrange = padded(offset + 54, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_zacc, tvbrange, value) end -- dissect payload of message type HIL_CONTROLS function payload_fns.payload_91(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -30381,32 +37225,43 @@ function payload_fns.payload_91(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_CONTROLS_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_CONTROLS_roll_ailerons, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_CONTROLS_pitch_elevator, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_CONTROLS_yaw_rudder, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_CONTROLS_throttle, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_CONTROLS_aux1, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_CONTROLS_aux2, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_CONTROLS_aux3, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_CONTROLS_aux4, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIL_CONTROLS_mode, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.HIL_CONTROLS_nav_mode, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_CONTROLS_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_roll_ailerons, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_pitch_elevator, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_yaw_rudder, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_throttle, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_CONTROLS_aux4, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_CONTROLS_mode, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_CONTROLS_nav_mode, tvbrange, value) end -- dissect payload of message type HIL_RC_INPUTS_RAW function payload_fns.payload_92(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 33 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 33) @@ -30414,38 +37269,52 @@ function payload_fns.payload_92(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan1_raw, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan2_raw, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan3_raw, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan4_raw, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan5_raw, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan6_raw, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan7_raw, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan8_raw, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan9_raw, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan10_raw, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan11_raw, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_chan12_raw, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_RC_INPUTS_RAW_rssi, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan1_raw, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan2_raw, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan3_raw, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan4_raw, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan5_raw, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan6_raw, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan7_raw, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan8_raw, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan9_raw, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan10_raw, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan11_raw, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_chan12_raw, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_RC_INPUTS_RAW_rssi, tvbrange, value) end -- dissect payload of message type HIL_ACTUATOR_CONTROLS function payload_fns.payload_93(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 81 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 81) @@ -30453,49 +37322,68 @@ function payload_fns.payload_93(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_time_usec, padded(field_offset, 8)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_0, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_1, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_2, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_3, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_4, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_5, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_6, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_7, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_8, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_9, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_10, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_11, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_12, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_13, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_14, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_15, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_mode, padded(field_offset, 1)) - dissect_flags_MAV_MODE_FLAG(subtree, "HIL_ACTUATOR_CONTROLS_mode", value) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_ACTUATOR_CONTROLS_flags, padded(field_offset, 8)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_time_usec, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_0, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_1, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_2, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_3, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_4, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_5, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_6, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_7, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_8, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_9, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_10, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_11, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_12, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_13, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_14, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_controls_15, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_mode, tvbrange, value) + dissect_flags_MAV_MODE_FLAG(subtree, "HIL_ACTUATOR_CONTROLS_mode", tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_ACTUATOR_CONTROLS_flags, tvbrange, value) end -- dissect payload of message type OPTICAL_FLOW function payload_fns.payload_100(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 34 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 34) @@ -30503,30 +37391,40 @@ function payload_fns.payload_100(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPTICAL_FLOW_time_usec, padded(field_offset, 8)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPTICAL_FLOW_sensor_id, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPTICAL_FLOW_flow_x, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OPTICAL_FLOW_flow_y, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_y, padded(field_offset, 4)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.OPTICAL_FLOW_quality, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPTICAL_FLOW_ground_distance, padded(field_offset, 4)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OPTICAL_FLOW_flow_rate_x, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.OPTICAL_FLOW_flow_rate_y, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.OPTICAL_FLOW_time_usec, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_sensor_id, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_x, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_comp_m_y, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_quality, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_ground_distance, tvbrange, value) + tvbrange = padded(offset + 26, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_rate_x, tvbrange, value) + tvbrange = padded(offset + 30, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_flow_rate_y, tvbrange, value) end -- dissect payload of message type GLOBAL_VISION_POSITION_ESTIMATE function payload_fns.payload_101(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 117 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 117) @@ -30534,68 +37432,97 @@ function payload_fns.payload_101(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_roll, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_pitch, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_yaw, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_0, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_1, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_2, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_3, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_4, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_5, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_6, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_7, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_8, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_9, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_10, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_11, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_12, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_13, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_14, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_15, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_16, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_17, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_18, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_19, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_20, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_reset_counter, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_roll, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_pitch, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_yaw, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_9, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_10, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_11, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_12, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_13, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_14, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_15, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_17, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_18, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_19, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_covariance_20, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GLOBAL_VISION_POSITION_ESTIMATE_reset_counter, tvbrange, value) end -- dissect payload of message type VISION_POSITION_ESTIMATE function payload_fns.payload_102(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 117 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 117) @@ -30603,68 +37530,97 @@ function payload_fns.payload_102(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_roll, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_pitch, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_yaw, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_0, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_1, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_2, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_3, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_4, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_5, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_6, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_7, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_8, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_9, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_10, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_11, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_12, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_13, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_14, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_15, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_16, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_17, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_18, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_19, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_20, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.VISION_POSITION_ESTIMATE_reset_counter, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_roll, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_pitch, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_yaw, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_9, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_10, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_11, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_12, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_13, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_14, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_15, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_17, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_18, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_19, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_covariance_20, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VISION_POSITION_ESTIMATE_reset_counter, tvbrange, value) end -- dissect payload of message type VISION_SPEED_ESTIMATE function payload_fns.payload_103(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 57 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 57) @@ -30672,38 +37628,52 @@ function payload_fns.payload_103(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_0, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_1, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_2, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_3, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_4, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_5, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_6, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_7, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_8, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.VISION_SPEED_ESTIMATE_reset_counter, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VISION_SPEED_ESTIMATE_reset_counter, tvbrange, value) end -- dissect payload of message type VICON_POSITION_ESTIMATE function payload_fns.payload_104(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 116 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 116) @@ -30711,66 +37681,94 @@ function payload_fns.payload_104(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_roll, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_pitch, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_yaw, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_0, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_1, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_2, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_3, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_4, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_5, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_6, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_7, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_8, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_9, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_10, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_11, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_12, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_13, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_14, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_15, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_16, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_17, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_18, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_19, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_20, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_roll, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_pitch, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_yaw, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_0, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_1, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_2, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_3, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_4, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_5, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_6, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_7, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_8, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_9, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_10, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_11, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_12, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_13, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_14, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_15, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_16, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_17, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_18, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_19, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VICON_POSITION_ESTIMATE_covariance_20, tvbrange, value) end -- dissect payload of message type HIGHRES_IMU function payload_fns.payload_105(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 63 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 63) @@ -30778,42 +37776,58 @@ function payload_fns.payload_105(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIGHRES_IMU_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIGHRES_IMU_xacc, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIGHRES_IMU_yacc, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIGHRES_IMU_zacc, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIGHRES_IMU_xgyro, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIGHRES_IMU_ygyro, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIGHRES_IMU_zgyro, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIGHRES_IMU_xmag, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIGHRES_IMU_ymag, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIGHRES_IMU_zmag, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.HIGHRES_IMU_abs_pressure, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.HIGHRES_IMU_diff_pressure, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.HIGHRES_IMU_pressure_alt, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.HIGHRES_IMU_temperature, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.HIGHRES_IMU_fields_updated, padded(field_offset, 2)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.HIGHRES_IMU_id, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIGHRES_IMU_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_xacc, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_yacc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_zacc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_zgyro, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_xmag, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_ymag, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_zmag, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_abs_pressure, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_diff_pressure, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_pressure_alt, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIGHRES_IMU_temperature, tvbrange, value) + tvbrange = padded(offset + 60, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGHRES_IMU_fields_updated, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGHRES_IMU_id, tvbrange, value) end -- dissect payload of message type OPTICAL_FLOW_RAD function payload_fns.payload_106(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -30821,34 +37835,46 @@ function payload_fns.payload_106(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_time_usec, padded(field_offset, 8)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_sensor_id, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_integration_time_us, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_xgyro, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_ygyro, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_zgyro, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_temperature, padded(field_offset, 2)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_quality, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_time_delta_distance_us, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OPTICAL_FLOW_RAD_distance, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_time_usec, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_sensor_id, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integration_time_us, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_integrated_zgyro, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_temperature, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_quality, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_time_delta_distance_us, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPTICAL_FLOW_RAD_distance, tvbrange, value) end -- dissect payload of message type HIL_SENSOR function payload_fns.payload_107(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 65 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 65) @@ -30856,42 +37882,58 @@ function payload_fns.payload_107(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_SENSOR_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_SENSOR_xacc, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_SENSOR_yacc, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_SENSOR_zacc, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_SENSOR_xgyro, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_SENSOR_ygyro, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_SENSOR_zgyro, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_SENSOR_xmag, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_SENSOR_ymag, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIL_SENSOR_zmag, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.HIL_SENSOR_abs_pressure, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.HIL_SENSOR_diff_pressure, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.HIL_SENSOR_pressure_alt, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.HIL_SENSOR_temperature, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.HIL_SENSOR_fields_updated, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.HIL_SENSOR_id, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_SENSOR_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_xacc, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_yacc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_zacc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_zgyro, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_xmag, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_ymag, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_zmag, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_abs_pressure, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_diff_pressure, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_pressure_alt, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_SENSOR_temperature, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_SENSOR_fields_updated, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_SENSOR_id, tvbrange, value) end -- dissect payload of message type SIM_STATE function payload_fns.payload_108(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 84 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 84) @@ -30899,52 +37941,73 @@ function payload_fns.payload_108(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SIM_STATE_q1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SIM_STATE_q2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SIM_STATE_q3, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SIM_STATE_q4, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SIM_STATE_roll, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SIM_STATE_pitch, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SIM_STATE_yaw, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SIM_STATE_xacc, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SIM_STATE_yacc, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SIM_STATE_zacc, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SIM_STATE_xgyro, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SIM_STATE_ygyro, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SIM_STATE_zgyro, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.SIM_STATE_lat, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.SIM_STATE_lon, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.SIM_STATE_alt, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.SIM_STATE_std_dev_horz, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.SIM_STATE_std_dev_vert, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.SIM_STATE_vn, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.SIM_STATE_ve, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.SIM_STATE_vd, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q3, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_q4, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_roll, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_pitch, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_yaw, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_xacc, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_yacc, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_zacc, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_xgyro, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_ygyro, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_zgyro, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_lat, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_lon, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_alt, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_std_dev_horz, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_std_dev_vert, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_vn, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_ve, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SIM_STATE_vd, tvbrange, value) end -- dissect payload of message type RADIO_STATUS function payload_fns.payload_109(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -30952,24 +38015,31 @@ function payload_fns.payload_109(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.RADIO_STATUS_rssi, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.RADIO_STATUS_remrssi, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RADIO_STATUS_txbuf, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.RADIO_STATUS_noise, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RADIO_STATUS_remnoise, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.RADIO_STATUS_rxerrors, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.RADIO_STATUS_fixed, padded(field_offset, 2)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_rssi, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_remrssi, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_txbuf, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_noise, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_remnoise, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_rxerrors, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RADIO_STATUS_fixed, tvbrange, value) end -- dissect payload of message type FILE_TRANSFER_PROTOCOL function payload_fns.payload_110(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 254 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 254) @@ -30977,518 +38047,772 @@ function payload_fns.payload_110(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_target_network, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_target_system, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_target_component, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_0, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_1, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_2, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_3, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_4, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_5, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_6, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_7, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_8, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_9, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_10, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_11, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_12, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_13, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_14, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_15, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_16, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_17, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_18, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_19, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_20, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_21, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_22, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_23, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_24, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_25, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_26, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_27, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_28, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_29, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_30, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_31, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_32, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_33, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_34, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_35, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_36, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_37, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_38, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_39, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_40, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_41, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_42, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_43, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_44, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_45, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_46, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_47, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_48, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_49, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_50, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_51, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_52, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_53, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_54, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_55, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_56, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_57, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_58, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_59, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_60, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_61, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_62, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_63, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_64, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_65, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_66, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_67, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_68, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_69, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_70, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_71, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_72, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_73, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_74, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_75, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_76, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_77, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_78, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_79, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_80, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_81, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_82, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_83, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_84, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_85, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_86, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_87, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_88, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_89, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_90, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_91, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_92, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_93, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_94, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_95, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_96, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_97, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_98, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_99, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_100, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_101, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_102, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_103, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_104, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_105, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_106, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_107, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_108, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_109, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_110, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_111, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_112, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_113, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_114, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_115, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_116, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_117, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_118, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_119, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_120, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_121, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_122, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_123, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_124, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_125, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_126, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_127, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_128, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_129, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_130, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_131, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_132, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_133, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_134, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_135, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_136, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_137, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_138, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_139, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_140, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_141, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_142, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_143, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_144, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_145, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_146, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_147, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_148, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_149, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_150, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_151, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_152, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_153, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_154, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_155, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_156, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_157, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_158, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_159, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_160, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_161, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_162, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_163, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_164, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_165, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_166, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_167, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_168, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_169, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_170, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_171, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_172, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_173, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_174, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_175, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_176, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_177, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_178, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_179, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_180, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_181, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_182, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_183, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_184, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_185, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_186, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_187, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_188, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_189, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_190, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_191, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_192, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_193, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_194, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_195, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_196, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_197, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_198, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_199, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_200, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_201, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_202, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_203, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_204, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_205, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_206, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_207, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_208, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_209, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_210, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_211, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_212, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_213, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_214, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_215, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_216, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_217, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_218, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_219, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_220, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_221, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_222, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_223, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_224, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_225, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_226, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_227, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_228, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_229, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_230, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_231, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_232, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_233, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_234, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_235, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_236, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_237, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_238, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_239, padded(field_offset, 1)) - field_offset = offset + 243 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_240, padded(field_offset, 1)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_241, padded(field_offset, 1)) - field_offset = offset + 245 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_242, padded(field_offset, 1)) - field_offset = offset + 246 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_243, padded(field_offset, 1)) - field_offset = offset + 247 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_244, padded(field_offset, 1)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_245, padded(field_offset, 1)) - field_offset = offset + 249 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_246, padded(field_offset, 1)) - field_offset = offset + 250 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_247, padded(field_offset, 1)) - field_offset = offset + 251 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_248, padded(field_offset, 1)) - field_offset = offset + 252 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_249, padded(field_offset, 1)) - field_offset = offset + 253 - subtree, value = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_250, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_target_network, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_target_system, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_target_component, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_0, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_1, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_2, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_3, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_4, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_5, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_6, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_7, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_8, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_9, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_10, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_11, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_12, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_13, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_14, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_15, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_16, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_17, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_18, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_19, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_20, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_21, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_22, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_23, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_24, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_25, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_26, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_27, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_28, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_29, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_30, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_31, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_32, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_33, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_34, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_35, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_36, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_37, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_38, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_39, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_40, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_41, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_42, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_43, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_44, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_45, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_46, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_47, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_48, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_49, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_50, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_51, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_52, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_53, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_54, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_55, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_56, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_57, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_58, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_59, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_60, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_61, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_62, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_63, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_64, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_65, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_66, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_67, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_68, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_69, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_70, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_71, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_72, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_73, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_74, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_75, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_76, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_77, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_78, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_79, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_80, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_81, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_82, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_83, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_84, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_85, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_86, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_87, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_88, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_89, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_90, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_91, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_92, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_93, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_94, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_95, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_96, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_97, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_98, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_99, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_100, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_101, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_102, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_103, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_104, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_105, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_106, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_107, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_108, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_109, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_110, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_111, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_112, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_113, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_114, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_115, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_116, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_117, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_118, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_119, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_120, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_121, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_122, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_123, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_124, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_125, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_126, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_127, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_128, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_129, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_130, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_131, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_132, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_133, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_134, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_135, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_136, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_137, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_138, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_139, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_140, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_141, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_142, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_143, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_144, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_145, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_146, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_147, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_148, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_149, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_150, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_151, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_152, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_153, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_154, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_155, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_156, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_157, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_158, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_159, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_160, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_161, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_162, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_163, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_164, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_165, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_166, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_167, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_168, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_169, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_170, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_171, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_172, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_173, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_174, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_175, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_176, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_177, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_178, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_179, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_180, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_181, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_182, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_183, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_184, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_185, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_186, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_187, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_188, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_189, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_190, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_191, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_192, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_193, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_194, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_195, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_196, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_197, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_198, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_199, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_200, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_201, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_202, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_203, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_204, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_205, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_206, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_207, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_208, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_209, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_210, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_211, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_212, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_213, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_214, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_215, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_216, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_217, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_218, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_219, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_220, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_221, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_222, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_223, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_224, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_225, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_226, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_227, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_228, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_229, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_230, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_231, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_232, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_233, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_234, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_235, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_236, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_237, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_238, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_239, tvbrange, value) + tvbrange = padded(offset + 243, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_240, tvbrange, value) + tvbrange = padded(offset + 244, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_241, tvbrange, value) + tvbrange = padded(offset + 245, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_242, tvbrange, value) + tvbrange = padded(offset + 246, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_243, tvbrange, value) + tvbrange = padded(offset + 247, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_244, tvbrange, value) + tvbrange = padded(offset + 248, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_245, tvbrange, value) + tvbrange = padded(offset + 249, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_246, tvbrange, value) + tvbrange = padded(offset + 250, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_247, tvbrange, value) + tvbrange = padded(offset + 251, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_248, tvbrange, value) + tvbrange = padded(offset + 252, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_249, tvbrange, value) + tvbrange = padded(offset + 253, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FILE_TRANSFER_PROTOCOL_payload_250, tvbrange, value) end -- dissect payload of message type TIMESYNC function payload_fns.payload_111(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -31496,14 +38820,16 @@ function payload_fns.payload_111(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.TIMESYNC_tc1, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.TIMESYNC_ts1, padded(field_offset, 8)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_int64() + subtree = tree:add_le(f.TIMESYNC_tc1, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_int64() + subtree = tree:add_le(f.TIMESYNC_ts1, tvbrange, value) end -- dissect payload of message type CAMERA_TRIGGER function payload_fns.payload_112(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 12 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 12) @@ -31511,14 +38837,16 @@ function payload_fns.payload_112(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_TRIGGER_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_TRIGGER_seq, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.CAMERA_TRIGGER_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_TRIGGER_seq, tvbrange, value) end -- dissect payload of message type HIL_GPS function payload_fns.payload_113(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 39 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 39) @@ -31526,40 +38854,55 @@ function payload_fns.payload_113(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_GPS_time_usec, padded(field_offset, 8)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.HIL_GPS_fix_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_GPS_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_GPS_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_GPS_alt, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_GPS_eph, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.HIL_GPS_epv, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_GPS_vel, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.HIL_GPS_vn, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_GPS_ve, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.HIL_GPS_vd, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_GPS_cog, padded(field_offset, 2)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.HIL_GPS_satellites_visible, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_GPS_id, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.HIL_GPS_yaw, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_GPS_time_usec, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_fix_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_GPS_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_GPS_lon, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_GPS_alt, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_eph, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_epv, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_vel, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_GPS_vn, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_GPS_ve, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_GPS_vd, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_cog, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_satellites_visible, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_id, tvbrange, value) + tvbrange = padded(offset + 37, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_GPS_yaw, tvbrange, value) end -- dissect payload of message type HIL_OPTICAL_FLOW function payload_fns.payload_114(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -31567,34 +38910,46 @@ function payload_fns.payload_114(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_time_usec, padded(field_offset, 8)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_sensor_id, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_integration_time_us, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_xgyro, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_ygyro, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_zgyro, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_temperature, padded(field_offset, 2)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_quality, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_time_delta_distance_us, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_OPTICAL_FLOW_distance, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_time_usec, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_sensor_id, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_integration_time_us, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_xgyro, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_ygyro, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_integrated_zgyro, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_temperature, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_quality, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_time_delta_distance_us, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_OPTICAL_FLOW_distance, tvbrange, value) end -- dissect payload of message type HIL_STATE_QUATERNION function payload_fns.payload_115(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 64 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 64) @@ -31602,48 +38957,67 @@ function payload_fns.payload_115(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_0, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_1, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_2, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_3, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_rollspeed, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_pitchspeed, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_yawspeed, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_lat, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_lon, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_alt, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_vx, padded(field_offset, 2)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_vy, padded(field_offset, 2)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_vz, padded(field_offset, 2)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_ind_airspeed, padded(field_offset, 2)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_true_airspeed, padded(field_offset, 2)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_xacc, padded(field_offset, 2)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_yacc, padded(field_offset, 2)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.HIL_STATE_QUATERNION_zacc, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_attitude_quaternion_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_rollspeed, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_yawspeed, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_lat, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_lon, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_alt, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_vx, tvbrange, value) + tvbrange = padded(offset + 50, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_vy, tvbrange, value) + tvbrange = padded(offset + 52, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_vz, tvbrange, value) + tvbrange = padded(offset + 54, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_ind_airspeed, tvbrange, value) + tvbrange = padded(offset + 56, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_true_airspeed, tvbrange, value) + tvbrange = padded(offset + 58, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_xacc, tvbrange, value) + tvbrange = padded(offset + 60, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_yacc, tvbrange, value) + tvbrange = padded(offset + 62, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIL_STATE_QUATERNION_zacc, tvbrange, value) end -- dissect payload of message type SCALED_IMU2 function payload_fns.payload_116(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 24 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 24) @@ -31651,32 +39025,43 @@ function payload_fns.payload_116(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SCALED_IMU2_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SCALED_IMU2_xacc, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.SCALED_IMU2_yacc, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SCALED_IMU2_zacc, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SCALED_IMU2_xgyro, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SCALED_IMU2_ygyro, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SCALED_IMU2_zgyro, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SCALED_IMU2_xmag, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SCALED_IMU2_ymag, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SCALED_IMU2_zmag, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SCALED_IMU2_temperature, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SCALED_IMU2_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_xacc, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_yacc, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_zacc, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_xgyro, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_ygyro, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_zgyro, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_xmag, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_ymag, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_zmag, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU2_temperature, tvbrange, value) end -- dissect payload of message type LOG_REQUEST_LIST function payload_fns.payload_117(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -31684,18 +39069,22 @@ function payload_fns.payload_117(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOG_REQUEST_LIST_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.LOG_REQUEST_LIST_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOG_REQUEST_LIST_start, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.LOG_REQUEST_LIST_end, padded(field_offset, 2)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_LIST_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_LIST_start, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_LIST_end, tvbrange, value) end -- dissect payload of message type LOG_ENTRY function payload_fns.payload_118(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 14 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 14) @@ -31703,20 +39092,25 @@ function payload_fns.payload_118(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOG_ENTRY_id, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.LOG_ENTRY_num_logs, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOG_ENTRY_last_log_num, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOG_ENTRY_time_utc, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOG_ENTRY_size, padded(field_offset, 4)) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ENTRY_id, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ENTRY_num_logs, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ENTRY_last_log_num, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ENTRY_time_utc, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ENTRY_size, tvbrange, value) end -- dissect payload of message type LOG_REQUEST_DATA function payload_fns.payload_119(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 12 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 12) @@ -31724,20 +39118,25 @@ function payload_fns.payload_119(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 10 - subtree, value = tree:add_le(f.LOG_REQUEST_DATA_target_system, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.LOG_REQUEST_DATA_target_component, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOG_REQUEST_DATA_id, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOG_REQUEST_DATA_ofs, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOG_REQUEST_DATA_count, padded(field_offset, 4)) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_DATA_target_system, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_DATA_target_component, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_DATA_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_DATA_ofs, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_DATA_count, tvbrange, value) end -- dissect payload of message type LOG_DATA function payload_fns.payload_120(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 97 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 97) @@ -31745,196 +39144,289 @@ function payload_fns.payload_120(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOG_DATA_id, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOG_DATA_ofs, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.LOG_DATA_count, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.LOG_DATA_data_0, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOG_DATA_data_1, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.LOG_DATA_data_2, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.LOG_DATA_data_3, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.LOG_DATA_data_4, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOG_DATA_data_5, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.LOG_DATA_data_6, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.LOG_DATA_data_7, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.LOG_DATA_data_8, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOG_DATA_data_9, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.LOG_DATA_data_10, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.LOG_DATA_data_11, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.LOG_DATA_data_12, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOG_DATA_data_13, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.LOG_DATA_data_14, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.LOG_DATA_data_15, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.LOG_DATA_data_16, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOG_DATA_data_17, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.LOG_DATA_data_18, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.LOG_DATA_data_19, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.LOG_DATA_data_20, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LOG_DATA_data_21, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.LOG_DATA_data_22, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.LOG_DATA_data_23, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.LOG_DATA_data_24, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.LOG_DATA_data_25, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.LOG_DATA_data_26, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.LOG_DATA_data_27, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.LOG_DATA_data_28, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.LOG_DATA_data_29, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.LOG_DATA_data_30, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.LOG_DATA_data_31, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.LOG_DATA_data_32, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.LOG_DATA_data_33, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.LOG_DATA_data_34, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.LOG_DATA_data_35, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.LOG_DATA_data_36, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.LOG_DATA_data_37, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.LOG_DATA_data_38, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.LOG_DATA_data_39, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.LOG_DATA_data_40, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.LOG_DATA_data_41, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.LOG_DATA_data_42, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.LOG_DATA_data_43, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.LOG_DATA_data_44, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.LOG_DATA_data_45, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.LOG_DATA_data_46, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.LOG_DATA_data_47, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.LOG_DATA_data_48, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.LOG_DATA_data_49, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.LOG_DATA_data_50, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.LOG_DATA_data_51, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.LOG_DATA_data_52, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.LOG_DATA_data_53, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.LOG_DATA_data_54, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.LOG_DATA_data_55, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.LOG_DATA_data_56, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.LOG_DATA_data_57, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.LOG_DATA_data_58, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.LOG_DATA_data_59, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.LOG_DATA_data_60, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.LOG_DATA_data_61, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.LOG_DATA_data_62, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.LOG_DATA_data_63, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.LOG_DATA_data_64, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.LOG_DATA_data_65, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.LOG_DATA_data_66, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.LOG_DATA_data_67, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.LOG_DATA_data_68, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.LOG_DATA_data_69, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.LOG_DATA_data_70, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.LOG_DATA_data_71, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.LOG_DATA_data_72, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.LOG_DATA_data_73, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.LOG_DATA_data_74, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.LOG_DATA_data_75, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.LOG_DATA_data_76, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.LOG_DATA_data_77, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.LOG_DATA_data_78, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.LOG_DATA_data_79, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.LOG_DATA_data_80, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.LOG_DATA_data_81, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.LOG_DATA_data_82, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.LOG_DATA_data_83, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.LOG_DATA_data_84, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.LOG_DATA_data_85, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.LOG_DATA_data_86, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.LOG_DATA_data_87, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.LOG_DATA_data_88, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.LOG_DATA_data_89, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_ofs, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_count, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_0, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_1, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_2, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_3, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_4, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_5, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_6, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_7, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_8, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_9, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_10, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_11, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_12, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_13, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_14, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_15, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_16, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_17, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_18, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_19, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_20, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_21, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_22, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_23, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_24, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_25, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_26, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_27, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_28, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_29, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_30, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_31, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_32, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_33, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_34, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_35, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_36, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_37, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_38, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_39, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_40, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_41, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_42, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_43, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_44, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_45, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_46, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_47, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_48, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_49, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_50, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_51, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_52, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_53, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_54, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_55, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_56, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_57, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_58, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_59, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_60, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_61, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_62, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_63, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_64, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_65, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_66, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_67, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_68, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_69, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_70, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_71, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_72, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_73, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_74, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_75, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_76, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_77, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_78, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_79, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_80, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_81, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_82, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_83, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_84, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_85, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_86, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_87, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_88, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_DATA_data_89, tvbrange, value) end -- dissect payload of message type LOG_ERASE function payload_fns.payload_121(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -31942,14 +39434,16 @@ function payload_fns.payload_121(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOG_ERASE_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.LOG_ERASE_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ERASE_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_ERASE_target_component, tvbrange, value) end -- dissect payload of message type LOG_REQUEST_END function payload_fns.payload_122(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -31957,14 +39451,16 @@ function payload_fns.payload_122(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOG_REQUEST_END_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.LOG_REQUEST_END_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_END_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOG_REQUEST_END_target_component, tvbrange, value) end -- dissect payload of message type GPS_INJECT_DATA function payload_fns.payload_123(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 113 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 113) @@ -31972,236 +39468,349 @@ function payload_fns.payload_123(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_len, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_0, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_1, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_2, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_3, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_4, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_5, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_6, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_7, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_8, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_9, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_10, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_11, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_12, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_13, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_14, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_15, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_16, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_17, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_18, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_19, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_20, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_21, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_22, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_23, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_24, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_25, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_26, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_27, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_28, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_29, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_30, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_31, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_32, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_33, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_34, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_35, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_36, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_37, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_38, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_39, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_40, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_41, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_42, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_43, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_44, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_45, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_46, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_47, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_48, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_49, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_50, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_51, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_52, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_53, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_54, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_55, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_56, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_57, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_58, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_59, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_60, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_61, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_62, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_63, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_64, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_65, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_66, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_67, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_68, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_69, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_70, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_71, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_72, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_73, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_74, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_75, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_76, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_77, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_78, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_79, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_80, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_81, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_82, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_83, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_84, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_85, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_86, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_87, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_88, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_89, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_90, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_91, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_92, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_93, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_94, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_95, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_96, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_97, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_98, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_99, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_100, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_101, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_102, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_103, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_104, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_105, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_106, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_107, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_108, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.GPS_INJECT_DATA_data_109, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_len, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_0, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_1, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_2, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_3, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_4, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_5, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_6, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_7, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_8, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_9, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_10, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_11, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_12, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_13, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_14, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_15, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_16, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_17, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_18, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_19, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_20, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_21, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_22, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_23, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_24, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_25, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_26, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_27, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_28, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_29, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_30, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_31, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_32, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_33, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_34, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_35, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_36, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_37, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_38, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_39, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_40, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_41, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_42, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_43, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_44, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_45, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_46, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_47, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_48, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_49, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_50, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_51, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_52, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_53, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_54, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_55, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_56, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_57, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_58, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_59, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_60, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_61, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_62, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_63, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_64, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_65, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_66, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_67, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_68, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_69, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_70, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_71, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_72, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_73, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_74, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_75, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_76, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_77, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_78, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_79, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_80, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_81, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_82, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_83, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_84, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_85, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_86, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_87, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_88, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_89, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_90, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_91, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_92, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_93, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_94, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_95, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_96, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_97, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_98, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_99, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_100, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_101, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_102, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_103, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_104, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_105, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_106, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_107, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_108, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INJECT_DATA_data_109, tvbrange, value) end -- dissect payload of message type GPS2_RAW function payload_fns.payload_124(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 57 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 57) @@ -32209,46 +39818,64 @@ function payload_fns.payload_124(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS2_RAW_time_usec, padded(field_offset, 8)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS2_RAW_fix_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS2_RAW_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS2_RAW_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS2_RAW_alt, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS2_RAW_eph, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.GPS2_RAW_epv, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS2_RAW_vel, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS2_RAW_cog, padded(field_offset, 2)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GPS2_RAW_satellites_visible, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS2_RAW_dgps_numch, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS2_RAW_dgps_age, padded(field_offset, 4)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.GPS2_RAW_yaw, padded(field_offset, 2)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.GPS2_RAW_alt_ellipsoid, padded(field_offset, 4)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.GPS2_RAW_h_acc, padded(field_offset, 4)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.GPS2_RAW_v_acc, padded(field_offset, 4)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.GPS2_RAW_vel_acc, padded(field_offset, 4)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.GPS2_RAW_hdg_acc, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GPS2_RAW_time_usec, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_fix_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RAW_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RAW_lon, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RAW_alt, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_eph, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_epv, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_vel, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_cog, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_satellites_visible, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_dgps_numch, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_dgps_age, tvbrange, value) + tvbrange = padded(offset + 35, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_yaw, tvbrange, value) + tvbrange = padded(offset + 37, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RAW_alt_ellipsoid, tvbrange, value) + tvbrange = padded(offset + 41, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_h_acc, tvbrange, value) + tvbrange = padded(offset + 45, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_v_acc, tvbrange, value) + tvbrange = padded(offset + 49, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_vel_acc, tvbrange, value) + tvbrange = padded(offset + 53, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RAW_hdg_acc, tvbrange, value) end -- dissect payload of message type POWER_STATUS function payload_fns.payload_125(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -32256,17 +39883,20 @@ function payload_fns.payload_125(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.POWER_STATUS_Vcc, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.POWER_STATUS_Vservo, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.POWER_STATUS_flags, padded(field_offset, 2)) - dissect_flags_MAV_POWER_STATUS(subtree, "POWER_STATUS_flags", value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POWER_STATUS_Vcc, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POWER_STATUS_Vservo, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.POWER_STATUS_flags, tvbrange, value) + dissect_flags_MAV_POWER_STATUS(subtree, "POWER_STATUS_flags", tvbrange, value) end -- dissect payload of message type SERIAL_CONTROL function payload_fns.payload_126(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 79 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 79) @@ -32274,161 +39904,236 @@ function payload_fns.payload_126(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 6 - subtree, value = tree:add_le(f.SERIAL_CONTROL_device, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.SERIAL_CONTROL_flags, padded(field_offset, 1)) - dissect_flags_SERIAL_CONTROL_FLAG(subtree, "SERIAL_CONTROL_flags", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SERIAL_CONTROL_timeout, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SERIAL_CONTROL_baudrate, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SERIAL_CONTROL_count, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_0, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_1, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_2, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_3, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_4, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_5, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_6, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_7, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_8, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_9, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_10, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_11, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_12, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_13, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_14, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_15, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_16, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_17, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_18, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_19, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_20, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_21, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_22, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_23, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_24, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_25, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_26, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_27, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_28, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_29, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_30, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_31, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_32, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_33, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_34, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_35, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_36, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_37, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_38, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_39, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_40, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_41, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_42, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_43, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_44, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_45, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_46, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_47, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_48, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_49, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_50, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_51, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_52, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_53, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_54, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_55, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_56, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_57, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_58, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_59, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_60, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_61, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_62, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_63, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_64, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_65, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_66, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_67, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_68, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.SERIAL_CONTROL_data_69, padded(field_offset, 1)) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_device, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_flags, tvbrange, value) + dissect_flags_SERIAL_CONTROL_FLAG(subtree, "SERIAL_CONTROL_flags", tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_timeout, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_baudrate, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_count, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_0, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_1, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_2, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_3, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_4, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_5, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_6, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_7, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_8, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_9, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_10, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_11, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_12, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_13, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_14, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_15, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_16, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_17, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_18, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_19, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_20, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_21, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_22, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_23, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_24, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_25, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_26, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_27, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_28, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_29, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_30, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_31, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_32, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_33, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_34, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_35, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_36, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_37, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_38, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_39, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_40, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_41, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_42, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_43, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_44, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_45, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_46, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_47, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_48, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_49, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_50, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_51, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_52, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_53, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_54, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_55, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_56, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_57, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_58, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_59, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_60, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_61, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_62, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_63, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_64, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_65, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_66, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_67, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_68, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SERIAL_CONTROL_data_69, tvbrange, value) end -- dissect payload of message type GPS_RTK function payload_fns.payload_127(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -32436,36 +40141,49 @@ function payload_fns.payload_127(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_RTK_time_last_baseline_ms, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS_RTK_rtk_receiver_id, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS_RTK_wn, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GPS_RTK_tow, padded(field_offset, 4)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.GPS_RTK_rtk_health, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS_RTK_rtk_rate, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GPS_RTK_nsats, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS_RTK_baseline_coords_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_RTK_baseline_a_mm, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_RTK_baseline_b_mm, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS_RTK_baseline_c_mm, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS_RTK_accuracy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS_RTK_iar_num_hypotheses, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_time_last_baseline_ms, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_rtk_receiver_id, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_wn, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_tow, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_rtk_health, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_rtk_rate, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_nsats, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_baseline_coords_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RTK_baseline_a_mm, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RTK_baseline_b_mm, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RTK_baseline_c_mm, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTK_accuracy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_RTK_iar_num_hypotheses, tvbrange, value) end -- dissect payload of message type GPS2_RTK function payload_fns.payload_128(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -32473,36 +40191,49 @@ function payload_fns.payload_128(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS2_RTK_time_last_baseline_ms, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS2_RTK_rtk_receiver_id, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS2_RTK_wn, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GPS2_RTK_tow, padded(field_offset, 4)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.GPS2_RTK_rtk_health, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS2_RTK_rtk_rate, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GPS2_RTK_nsats, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS2_RTK_baseline_coords_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS2_RTK_baseline_a_mm, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS2_RTK_baseline_b_mm, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS2_RTK_baseline_c_mm, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS2_RTK_accuracy, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS2_RTK_iar_num_hypotheses, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_time_last_baseline_ms, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_rtk_receiver_id, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_wn, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_tow, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_rtk_health, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_rtk_rate, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_nsats, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_baseline_coords_type, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RTK_baseline_a_mm, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RTK_baseline_b_mm, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RTK_baseline_c_mm, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS2_RTK_accuracy, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS2_RTK_iar_num_hypotheses, tvbrange, value) end -- dissect payload of message type SCALED_IMU3 function payload_fns.payload_129(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 24 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 24) @@ -32510,32 +40241,43 @@ function payload_fns.payload_129(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SCALED_IMU3_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SCALED_IMU3_xacc, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.SCALED_IMU3_yacc, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SCALED_IMU3_zacc, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SCALED_IMU3_xgyro, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SCALED_IMU3_ygyro, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SCALED_IMU3_zgyro, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SCALED_IMU3_xmag, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SCALED_IMU3_ymag, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SCALED_IMU3_zmag, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SCALED_IMU3_temperature, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SCALED_IMU3_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_xacc, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_yacc, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_zacc, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_xgyro, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_ygyro, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_zgyro, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_xmag, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_ymag, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_zmag, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_IMU3_temperature, tvbrange, value) end -- dissect payload of message type DATA_TRANSMISSION_HANDSHAKE function payload_fns.payload_130(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 13 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 13) @@ -32543,24 +40285,31 @@ function payload_fns.payload_130(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 10 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_type, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_size, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_width, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_height, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_packets, padded(field_offset, 2)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_payload, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_jpg_quality, padded(field_offset, 1)) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_type, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_size, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_width, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_height, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_packets, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_payload, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DATA_TRANSMISSION_HANDSHAKE_jpg_quality, tvbrange, value) end -- dissect payload of message type ENCAPSULATED_DATA function payload_fns.payload_131(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 255 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 255) @@ -32568,518 +40317,772 @@ function payload_fns.payload_131(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_seqnr, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_20, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_21, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_22, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_23, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_24, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_25, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_26, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_27, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_28, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_29, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_30, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_31, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_32, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_33, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_34, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_35, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_36, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_37, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_38, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_39, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_40, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_41, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_42, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_43, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_44, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_45, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_46, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_47, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_48, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_49, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_50, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_51, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_52, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_53, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_54, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_55, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_56, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_57, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_58, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_59, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_60, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_61, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_62, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_63, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_64, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_65, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_66, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_67, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_68, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_69, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_70, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_71, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_72, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_73, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_74, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_75, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_76, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_77, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_78, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_79, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_80, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_81, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_82, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_83, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_84, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_85, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_86, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_87, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_88, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_89, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_90, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_91, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_92, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_93, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_94, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_95, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_96, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_97, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_98, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_99, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_100, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_101, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_102, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_103, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_104, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_105, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_106, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_107, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_108, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_109, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_110, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_111, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_112, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_113, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_114, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_115, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_116, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_117, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_118, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_119, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_120, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_121, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_122, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_123, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_124, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_125, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_126, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_127, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_128, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_129, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_130, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_131, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_132, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_133, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_134, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_135, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_136, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_137, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_138, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_139, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_140, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_141, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_142, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_143, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_144, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_145, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_146, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_147, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_148, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_149, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_150, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_151, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_152, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_153, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_154, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_155, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_156, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_157, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_158, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_159, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_160, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_161, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_162, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_163, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_164, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_165, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_166, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_167, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_168, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_169, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_170, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_171, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_172, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_173, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_174, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_175, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_176, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_177, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_178, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_179, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_180, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_181, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_182, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_183, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_184, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_185, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_186, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_187, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_188, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_189, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_190, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_191, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_192, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_193, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_194, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_195, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_196, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_197, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_198, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_199, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_200, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_201, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_202, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_203, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_204, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_205, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_206, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_207, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_208, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_209, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_210, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_211, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_212, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_213, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_214, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_215, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_216, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_217, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_218, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_219, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_220, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_221, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_222, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_223, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_224, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_225, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_226, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_227, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_228, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_229, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_230, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_231, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_232, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_233, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_234, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_235, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_236, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_237, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_238, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_239, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_240, padded(field_offset, 1)) - field_offset = offset + 243 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_241, padded(field_offset, 1)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_242, padded(field_offset, 1)) - field_offset = offset + 245 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_243, padded(field_offset, 1)) - field_offset = offset + 246 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_244, padded(field_offset, 1)) - field_offset = offset + 247 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_245, padded(field_offset, 1)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_246, padded(field_offset, 1)) - field_offset = offset + 249 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_247, padded(field_offset, 1)) - field_offset = offset + 250 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_248, padded(field_offset, 1)) - field_offset = offset + 251 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_249, padded(field_offset, 1)) - field_offset = offset + 252 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_250, padded(field_offset, 1)) - field_offset = offset + 253 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_251, padded(field_offset, 1)) - field_offset = offset + 254 - subtree, value = tree:add_le(f.ENCAPSULATED_DATA_data_252, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_seqnr, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_20, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_21, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_22, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_23, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_24, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_25, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_26, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_27, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_28, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_29, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_30, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_31, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_32, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_33, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_34, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_35, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_36, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_37, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_38, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_39, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_40, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_41, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_42, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_43, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_44, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_45, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_46, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_47, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_48, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_49, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_50, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_51, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_52, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_53, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_54, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_55, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_56, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_57, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_58, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_59, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_60, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_61, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_62, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_63, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_64, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_65, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_66, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_67, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_68, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_69, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_70, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_71, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_72, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_73, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_74, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_75, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_76, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_77, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_78, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_79, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_80, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_81, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_82, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_83, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_84, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_85, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_86, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_87, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_88, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_89, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_90, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_91, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_92, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_93, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_94, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_95, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_96, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_97, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_98, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_99, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_100, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_101, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_102, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_103, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_104, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_105, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_106, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_107, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_108, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_109, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_110, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_111, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_112, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_113, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_114, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_115, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_116, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_117, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_118, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_119, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_120, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_121, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_122, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_123, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_124, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_125, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_126, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_127, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_128, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_129, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_130, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_131, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_132, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_133, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_134, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_135, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_136, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_137, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_138, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_139, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_140, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_141, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_142, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_143, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_144, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_145, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_146, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_147, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_148, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_149, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_150, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_151, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_152, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_153, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_154, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_155, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_156, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_157, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_158, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_159, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_160, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_161, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_162, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_163, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_164, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_165, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_166, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_167, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_168, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_169, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_170, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_171, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_172, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_173, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_174, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_175, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_176, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_177, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_178, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_179, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_180, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_181, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_182, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_183, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_184, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_185, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_186, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_187, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_188, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_189, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_190, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_191, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_192, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_193, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_194, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_195, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_196, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_197, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_198, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_199, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_200, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_201, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_202, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_203, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_204, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_205, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_206, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_207, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_208, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_209, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_210, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_211, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_212, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_213, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_214, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_215, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_216, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_217, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_218, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_219, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_220, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_221, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_222, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_223, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_224, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_225, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_226, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_227, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_228, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_229, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_230, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_231, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_232, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_233, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_234, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_235, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_236, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_237, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_238, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_239, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_240, tvbrange, value) + tvbrange = padded(offset + 243, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_241, tvbrange, value) + tvbrange = padded(offset + 244, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_242, tvbrange, value) + tvbrange = padded(offset + 245, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_243, tvbrange, value) + tvbrange = padded(offset + 246, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_244, tvbrange, value) + tvbrange = padded(offset + 247, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_245, tvbrange, value) + tvbrange = padded(offset + 248, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_246, tvbrange, value) + tvbrange = padded(offset + 249, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_247, tvbrange, value) + tvbrange = padded(offset + 250, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_248, tvbrange, value) + tvbrange = padded(offset + 251, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_249, tvbrange, value) + tvbrange = padded(offset + 252, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_250, tvbrange, value) + tvbrange = padded(offset + 253, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_251, tvbrange, value) + tvbrange = padded(offset + 254, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ENCAPSULATED_DATA_data_252, tvbrange, value) end -- dissect payload of message type DISTANCE_SENSOR function payload_fns.payload_132(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 39 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 39) @@ -33087,40 +41090,55 @@ function payload_fns.payload_132(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_min_distance, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_max_distance, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_current_distance, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_type, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_id, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_orientation, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_covariance, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_horizontal_fov, padded(field_offset, 4)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_vertical_fov, padded(field_offset, 4)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_quaternion_0, padded(field_offset, 4)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_quaternion_1, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_quaternion_2, padded(field_offset, 4)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_quaternion_3, padded(field_offset, 4)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.DISTANCE_SENSOR_signal_quality, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_min_distance, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_max_distance, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_current_distance, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_type, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_id, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_orientation, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_covariance, tvbrange, value) + tvbrange = padded(offset + 14, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DISTANCE_SENSOR_horizontal_fov, tvbrange, value) + tvbrange = padded(offset + 18, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DISTANCE_SENSOR_vertical_fov, tvbrange, value) + tvbrange = padded(offset + 22, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DISTANCE_SENSOR_quaternion_0, tvbrange, value) + tvbrange = padded(offset + 26, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DISTANCE_SENSOR_quaternion_1, tvbrange, value) + tvbrange = padded(offset + 30, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DISTANCE_SENSOR_quaternion_2, tvbrange, value) + tvbrange = padded(offset + 34, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DISTANCE_SENSOR_quaternion_3, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DISTANCE_SENSOR_signal_quality, tvbrange, value) end -- dissect payload of message type TERRAIN_REQUEST function payload_fns.payload_133(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 18 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 18) @@ -33128,18 +41146,22 @@ function payload_fns.payload_133(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.TERRAIN_REQUEST_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.TERRAIN_REQUEST_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.TERRAIN_REQUEST_grid_spacing, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.TERRAIN_REQUEST_mask, padded(field_offset, 8)) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_REQUEST_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_REQUEST_lon, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TERRAIN_REQUEST_grid_spacing, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.TERRAIN_REQUEST_mask, tvbrange, value) end -- dissect payload of message type TERRAIN_DATA function payload_fns.payload_134(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 43 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 43) @@ -33147,50 +41169,70 @@ function payload_fns.payload_134(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.TERRAIN_DATA_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.TERRAIN_DATA_lon, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.TERRAIN_DATA_grid_spacing, padded(field_offset, 2)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.TERRAIN_DATA_gridbit, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_0, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_1, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_2, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_3, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_4, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_5, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_6, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_7, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_8, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_9, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_10, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_11, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_12, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_13, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_14, padded(field_offset, 2)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.TERRAIN_DATA_data_15, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_lon, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TERRAIN_DATA_grid_spacing, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TERRAIN_DATA_gridbit, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_0, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_1, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_2, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_3, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_4, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_5, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_6, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_7, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_8, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_9, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_10, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_11, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_12, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_13, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_14, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_DATA_data_15, tvbrange, value) end -- dissect payload of message type TERRAIN_CHECK function payload_fns.payload_135(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 8 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 8) @@ -33198,14 +41240,16 @@ function payload_fns.payload_135(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.TERRAIN_CHECK_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.TERRAIN_CHECK_lon, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_CHECK_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_CHECK_lon, tvbrange, value) end -- dissect payload of message type TERRAIN_REPORT function payload_fns.payload_136(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 22 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 22) @@ -33213,24 +41257,31 @@ function payload_fns.payload_136(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.TERRAIN_REPORT_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.TERRAIN_REPORT_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.TERRAIN_REPORT_spacing, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.TERRAIN_REPORT_terrain_height, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.TERRAIN_REPORT_current_height, padded(field_offset, 4)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.TERRAIN_REPORT_pending, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.TERRAIN_REPORT_loaded, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_REPORT_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.TERRAIN_REPORT_lon, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TERRAIN_REPORT_spacing, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TERRAIN_REPORT_terrain_height, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.TERRAIN_REPORT_current_height, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TERRAIN_REPORT_pending, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TERRAIN_REPORT_loaded, tvbrange, value) end -- dissect payload of message type SCALED_PRESSURE2 function payload_fns.payload_137(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -33238,20 +41289,25 @@ function payload_fns.payload_137(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SCALED_PRESSURE2_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SCALED_PRESSURE2_press_abs, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SCALED_PRESSURE2_press_diff, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SCALED_PRESSURE2_temperature, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SCALED_PRESSURE2_temperature_press_diff, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SCALED_PRESSURE2_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SCALED_PRESSURE2_press_abs, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SCALED_PRESSURE2_press_diff, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_PRESSURE2_temperature, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_PRESSURE2_temperature_press_diff, tvbrange, value) end -- dissect payload of message type ATT_POS_MOCAP function payload_fns.payload_138(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 120 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 120) @@ -33259,68 +41315,97 @@ function payload_fns.payload_138(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_q_0, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_q_1, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_q_2, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_q_3, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_x, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_y, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_z, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_0, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_1, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_2, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_3, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_4, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_5, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_6, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_7, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_8, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_9, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_10, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_11, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_12, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_13, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_14, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_15, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_16, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_17, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_18, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_19, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.ATT_POS_MOCAP_covariance_20, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ATT_POS_MOCAP_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_q_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_q_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_q_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_q_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_x, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_y, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_z, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_0, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_1, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_2, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_3, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_4, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_5, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_6, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_7, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_8, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_9, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_10, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_11, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_12, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_13, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_14, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_15, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_16, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_17, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_18, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_19, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ATT_POS_MOCAP_covariance_20, tvbrange, value) end -- dissect payload of message type SET_ACTUATOR_CONTROL_TARGET function payload_fns.payload_139(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 43 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 43) @@ -33328,34 +41413,46 @@ function payload_fns.payload_139(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_time_usec, padded(field_offset, 8)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_group_mlx, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_target_system, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_target_component, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_0, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_1, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_2, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_3, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_4, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_5, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_6, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_7, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_time_usec, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_group_mlx, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_target_system, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_target_component, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_5, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_6, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_ACTUATOR_CONTROL_TARGET_controls_7, tvbrange, value) end -- dissect payload of message type ACTUATOR_CONTROL_TARGET function payload_fns.payload_140(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 41 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 41) @@ -33363,30 +41460,40 @@ function payload_fns.payload_140(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_time_usec, padded(field_offset, 8)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_group_mlx, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_0, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_1, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_2, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_3, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_4, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_5, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_6, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_7, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_time_usec, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_group_mlx, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_5, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_6, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_CONTROL_TARGET_controls_7, tvbrange, value) end -- dissect payload of message type ALTITUDE function payload_fns.payload_141(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 32 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 32) @@ -33394,24 +41501,31 @@ function payload_fns.payload_141(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ALTITUDE_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ALTITUDE_altitude_monotonic, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ALTITUDE_altitude_amsl, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ALTITUDE_altitude_local, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ALTITUDE_altitude_relative, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ALTITUDE_altitude_terrain, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ALTITUDE_bottom_clearance, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ALTITUDE_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ALTITUDE_altitude_monotonic, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ALTITUDE_altitude_amsl, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ALTITUDE_altitude_local, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ALTITUDE_altitude_relative, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ALTITUDE_altitude_terrain, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ALTITUDE_bottom_clearance, tvbrange, value) end -- dissect payload of message type RESOURCE_REQUEST function payload_fns.payload_142(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 243 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 243) @@ -33419,496 +41533,739 @@ function payload_fns.payload_142(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_request_id, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_type, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_20, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_21, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_22, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_23, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_24, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_25, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_26, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_27, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_28, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_29, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_30, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_31, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_32, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_33, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_34, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_35, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_36, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_37, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_38, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_39, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_40, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_41, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_42, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_43, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_44, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_45, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_46, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_47, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_48, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_49, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_50, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_51, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_52, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_53, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_54, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_55, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_56, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_57, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_58, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_59, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_60, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_61, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_62, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_63, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_64, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_65, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_66, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_67, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_68, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_69, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_70, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_71, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_72, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_73, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_74, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_75, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_76, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_77, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_78, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_79, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_80, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_81, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_82, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_83, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_84, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_85, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_86, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_87, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_88, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_89, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_90, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_91, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_92, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_93, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_94, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_95, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_96, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_97, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_98, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_99, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_100, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_101, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_102, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_103, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_104, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_105, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_106, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_107, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_108, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_109, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_110, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_111, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_112, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_113, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_114, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_115, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_116, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_117, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_118, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_uri_119, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_transfer_type, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_0, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_1, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_2, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_3, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_4, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_5, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_6, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_7, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_8, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_9, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_10, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_11, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_12, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_13, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_14, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_15, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_16, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_17, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_18, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_19, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_20, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_21, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_22, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_23, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_24, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_25, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_26, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_27, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_28, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_29, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_30, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_31, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_32, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_33, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_34, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_35, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_36, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_37, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_38, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_39, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_40, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_41, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_42, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_43, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_44, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_45, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_46, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_47, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_48, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_49, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_50, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_51, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_52, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_53, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_54, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_55, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_56, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_57, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_58, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_59, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_60, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_61, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_62, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_63, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_64, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_65, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_66, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_67, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_68, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_69, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_70, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_71, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_72, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_73, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_74, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_75, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_76, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_77, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_78, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_79, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_80, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_81, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_82, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_83, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_84, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_85, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_86, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_87, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_88, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_89, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_90, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_91, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_92, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_93, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_94, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_95, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_96, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_97, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_98, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_99, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_100, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_101, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_102, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_103, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_104, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_105, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_106, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_107, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_108, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_109, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_110, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_111, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_112, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_113, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_114, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_115, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_116, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_117, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_118, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.RESOURCE_REQUEST_storage_119, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_request_id, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_type, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_20, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_21, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_22, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_23, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_24, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_25, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_26, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_27, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_28, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_29, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_30, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_31, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_32, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_33, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_34, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_35, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_36, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_37, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_38, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_39, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_40, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_41, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_42, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_43, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_44, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_45, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_46, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_47, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_48, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_49, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_50, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_51, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_52, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_53, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_54, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_55, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_56, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_57, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_58, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_59, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_60, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_61, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_62, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_63, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_64, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_65, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_66, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_67, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_68, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_69, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_70, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_71, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_72, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_73, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_74, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_75, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_76, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_77, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_78, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_79, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_80, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_81, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_82, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_83, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_84, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_85, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_86, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_87, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_88, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_89, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_90, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_91, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_92, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_93, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_94, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_95, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_96, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_97, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_98, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_99, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_100, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_101, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_102, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_103, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_104, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_105, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_106, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_107, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_108, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_109, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_110, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_111, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_112, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_113, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_114, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_115, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_116, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_117, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_118, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_uri_119, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_transfer_type, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_0, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_1, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_2, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_3, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_4, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_5, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_6, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_7, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_8, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_9, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_10, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_11, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_12, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_13, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_14, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_15, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_16, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_17, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_18, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_19, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_20, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_21, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_22, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_23, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_24, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_25, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_26, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_27, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_28, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_29, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_30, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_31, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_32, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_33, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_34, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_35, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_36, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_37, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_38, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_39, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_40, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_41, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_42, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_43, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_44, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_45, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_46, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_47, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_48, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_49, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_50, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_51, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_52, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_53, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_54, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_55, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_56, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_57, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_58, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_59, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_60, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_61, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_62, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_63, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_64, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_65, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_66, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_67, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_68, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_69, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_70, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_71, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_72, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_73, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_74, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_75, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_76, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_77, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_78, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_79, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_80, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_81, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_82, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_83, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_84, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_85, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_86, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_87, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_88, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_89, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_90, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_91, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_92, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_93, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_94, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_95, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_96, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_97, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_98, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_99, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_100, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_101, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_102, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_103, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_104, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_105, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_106, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_107, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_108, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_109, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_110, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_111, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_112, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_113, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_114, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_115, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_116, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_117, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_118, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RESOURCE_REQUEST_storage_119, tvbrange, value) end -- dissect payload of message type SCALED_PRESSURE3 function payload_fns.payload_143(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -33916,20 +42273,25 @@ function payload_fns.payload_143(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.SCALED_PRESSURE3_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SCALED_PRESSURE3_press_abs, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SCALED_PRESSURE3_press_diff, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SCALED_PRESSURE3_temperature, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SCALED_PRESSURE3_temperature_press_diff, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SCALED_PRESSURE3_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SCALED_PRESSURE3_press_abs, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SCALED_PRESSURE3_press_diff, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_PRESSURE3_temperature, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.SCALED_PRESSURE3_temperature_press_diff, tvbrange, value) end -- dissect payload of message type FOLLOW_TARGET function payload_fns.payload_144(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 93 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 93) @@ -33937,54 +42299,76 @@ function payload_fns.payload_144(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.FOLLOW_TARGET_timestamp, padded(field_offset, 8)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.FOLLOW_TARGET_est_capabilities, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.FOLLOW_TARGET_lat, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.FOLLOW_TARGET_lon, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.FOLLOW_TARGET_alt, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.FOLLOW_TARGET_vel_0, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.FOLLOW_TARGET_vel_1, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.FOLLOW_TARGET_vel_2, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.FOLLOW_TARGET_acc_0, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.FOLLOW_TARGET_acc_1, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.FOLLOW_TARGET_acc_2, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.FOLLOW_TARGET_attitude_q_0, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.FOLLOW_TARGET_attitude_q_1, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.FOLLOW_TARGET_attitude_q_2, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.FOLLOW_TARGET_attitude_q_3, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.FOLLOW_TARGET_rates_0, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.FOLLOW_TARGET_rates_1, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.FOLLOW_TARGET_rates_2, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.FOLLOW_TARGET_position_cov_0, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.FOLLOW_TARGET_position_cov_1, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.FOLLOW_TARGET_position_cov_2, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.FOLLOW_TARGET_custom_state, padded(field_offset, 8)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FOLLOW_TARGET_timestamp, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FOLLOW_TARGET_est_capabilities, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.FOLLOW_TARGET_lat, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.FOLLOW_TARGET_lon, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_alt, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_vel_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_vel_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_vel_2, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_acc_0, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_acc_1, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_acc_2, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_attitude_q_0, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_attitude_q_1, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_attitude_q_2, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_attitude_q_3, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_rates_0, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_rates_1, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_rates_2, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_position_cov_0, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_position_cov_1, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.FOLLOW_TARGET_position_cov_2, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FOLLOW_TARGET_custom_state, tvbrange, value) end -- dissect payload of message type CONTROL_SYSTEM_STATE function payload_fns.payload_146(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 100 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 100) @@ -33992,58 +42376,82 @@ function payload_fns.payload_146(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_x_acc, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_y_acc, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_z_acc, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_x_vel, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_y_vel, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_z_vel, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_x_pos, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_y_pos, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_z_pos, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_airspeed, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_vel_variance_0, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_vel_variance_1, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_vel_variance_2, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_pos_variance_0, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_pos_variance_1, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_pos_variance_2, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_q_0, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_q_1, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_q_2, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_q_3, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_roll_rate, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_pitch_rate, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.CONTROL_SYSTEM_STATE_yaw_rate, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_x_acc, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_y_acc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_z_acc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_x_vel, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_y_vel, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_z_vel, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_x_pos, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_y_pos, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_z_pos, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_airspeed, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_vel_variance_0, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_vel_variance_1, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_vel_variance_2, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_pos_variance_0, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_pos_variance_1, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_pos_variance_2, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_q_0, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_q_1, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_q_2, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_q_3, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_roll_rate, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CONTROL_SYSTEM_STATE_yaw_rate, tvbrange, value) end -- dissect payload of message type BATTERY_STATUS function payload_fns.payload_147(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 54 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 54) @@ -34051,63 +42459,89 @@ function payload_fns.payload_147(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 32 - subtree, value = tree:add_le(f.BATTERY_STATUS_id, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.BATTERY_STATUS_battery_function, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.BATTERY_STATUS_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.BATTERY_STATUS_temperature, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_0, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_1, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_2, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_3, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_4, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_5, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_6, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_7, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_8, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_9, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.BATTERY_STATUS_current_battery, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.BATTERY_STATUS_current_consumed, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.BATTERY_STATUS_energy_consumed, padded(field_offset, 4)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.BATTERY_STATUS_battery_remaining, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.BATTERY_STATUS_time_remaining, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.BATTERY_STATUS_charge_state, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_ext_0, padded(field_offset, 2)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_ext_1, padded(field_offset, 2)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_ext_2, padded(field_offset, 2)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.BATTERY_STATUS_voltages_ext_3, padded(field_offset, 2)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.BATTERY_STATUS_mode, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.BATTERY_STATUS_fault_bitmask, padded(field_offset, 4)) - dissect_flags_MAV_BATTERY_FAULT(subtree, "BATTERY_STATUS_fault_bitmask", value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_id, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_battery_function, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_type, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY_STATUS_temperature, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_0, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_1, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_2, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_3, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_4, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_5, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_6, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_7, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_8, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_9, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY_STATUS_current_battery, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY_STATUS_current_consumed, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY_STATUS_energy_consumed, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY_STATUS_battery_remaining, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.BATTERY_STATUS_time_remaining, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_charge_state, tvbrange, value) + tvbrange = padded(offset + 41, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_ext_0, tvbrange, value) + tvbrange = padded(offset + 43, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_ext_1, tvbrange, value) + tvbrange = padded(offset + 45, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_ext_2, tvbrange, value) + tvbrange = padded(offset + 47, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_voltages_ext_3, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_mode, tvbrange, value) + tvbrange = padded(offset + 50, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BATTERY_STATUS_fault_bitmask, tvbrange, value) + dissect_flags_MAV_BATTERY_FAULT(subtree, "BATTERY_STATUS_fault_bitmask", tvbrange, value) end -- dissect payload of message type AUTOPILOT_VERSION function payload_fns.payload_148(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 78 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 78) @@ -34115,111 +42549,161 @@ function payload_fns.payload_148(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_capabilities, padded(field_offset, 8)) - dissect_flags_MAV_PROTOCOL_CAPABILITY(subtree, "AUTOPILOT_VERSION_capabilities", value) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_sw_version, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_sw_version, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_sw_version, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_board_version, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_0, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_1, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_2, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_3, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_4, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_5, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_6, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_7, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_0, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_1, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_2, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_3, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_4, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_5, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_6, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_7, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_0, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_1, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_2, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_3, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_4, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_5, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_6, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_7, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_vendor_id, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_product_id, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid, padded(field_offset, 8)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_0, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_1, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_2, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_3, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_4, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_5, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_6, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_7, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_8, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_9, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_10, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_11, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_12, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_13, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_14, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_15, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_16, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.AUTOPILOT_VERSION_uid2_17, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.AUTOPILOT_VERSION_capabilities, tvbrange, value) + dissect_flags_MAV_PROTOCOL_CAPABILITY(subtree, "AUTOPILOT_VERSION_capabilities", tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_sw_version, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_sw_version, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_sw_version, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_board_version, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_0, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_1, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_2, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_3, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_4, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_5, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_6, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_flight_custom_version_7, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_0, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_1, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_2, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_3, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_4, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_5, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_6, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_middleware_custom_version_7, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_0, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_1, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_2, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_3, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_4, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_5, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_6, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_os_custom_version_7, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_vendor_id, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_product_id, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_0, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_1, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_2, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_3, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_4, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_5, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_6, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_7, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_8, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_9, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_10, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_11, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_12, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_13, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_14, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_15, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_16, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_VERSION_uid2_17, tvbrange, value) end -- dissect payload of message type LANDING_TARGET function payload_fns.payload_149(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 60 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 60) @@ -34227,44 +42711,61 @@ function payload_fns.payload_149(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LANDING_TARGET_time_usec, padded(field_offset, 8)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LANDING_TARGET_target_num, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.LANDING_TARGET_frame, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LANDING_TARGET_angle_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LANDING_TARGET_angle_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LANDING_TARGET_distance, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LANDING_TARGET_size_x, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LANDING_TARGET_size_y, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.LANDING_TARGET_x, padded(field_offset, 4)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.LANDING_TARGET_y, padded(field_offset, 4)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.LANDING_TARGET_z, padded(field_offset, 4)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.LANDING_TARGET_q_0, padded(field_offset, 4)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.LANDING_TARGET_q_1, padded(field_offset, 4)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.LANDING_TARGET_q_2, padded(field_offset, 4)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.LANDING_TARGET_q_3, padded(field_offset, 4)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.LANDING_TARGET_type, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.LANDING_TARGET_position_valid, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.LANDING_TARGET_time_usec, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LANDING_TARGET_target_num, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LANDING_TARGET_frame, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_angle_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_angle_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_distance, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_size_x, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_size_y, tvbrange, value) + tvbrange = padded(offset + 30, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_x, tvbrange, value) + tvbrange = padded(offset + 34, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_y, tvbrange, value) + tvbrange = padded(offset + 38, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_z, tvbrange, value) + tvbrange = padded(offset + 42, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_q_0, tvbrange, value) + tvbrange = padded(offset + 46, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_q_1, tvbrange, value) + tvbrange = padded(offset + 50, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_q_2, tvbrange, value) + tvbrange = padded(offset + 54, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LANDING_TARGET_q_3, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LANDING_TARGET_type, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LANDING_TARGET_position_valid, tvbrange, value) end -- dissect payload of message type FENCE_STATUS function payload_fns.payload_162(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -34272,20 +42773,25 @@ function payload_fns.payload_162(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 6 - subtree, value = tree:add_le(f.FENCE_STATUS_breach_status, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.FENCE_STATUS_breach_count, padded(field_offset, 2)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.FENCE_STATUS_breach_type, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.FENCE_STATUS_breach_time, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.FENCE_STATUS_breach_mitigation, padded(field_offset, 1)) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_STATUS_breach_status, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_STATUS_breach_count, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_STATUS_breach_type, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_STATUS_breach_time, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FENCE_STATUS_breach_mitigation, tvbrange, value) end -- dissect payload of message type MAG_CAL_REPORT function payload_fns.payload_192(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 54 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 54) @@ -34293,46 +42799,64 @@ function payload_fns.payload_192(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_compass_id, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_cal_mask, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_cal_status, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_autosaved, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_fitness, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_ofs_x, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_ofs_y, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_ofs_z, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_diag_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_diag_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_diag_z, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_offdiag_x, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_offdiag_y, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_offdiag_z, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_orientation_confidence, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_old_orientation, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_new_orientation, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.MAG_CAL_REPORT_scale_factor, padded(field_offset, 4)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_REPORT_compass_id, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_REPORT_cal_mask, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_REPORT_cal_status, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_REPORT_autosaved, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_fitness, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_ofs_x, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_ofs_y, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_ofs_z, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_diag_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_diag_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_diag_z, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_offdiag_x, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_offdiag_y, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_offdiag_z, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_orientation_confidence, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_REPORT_old_orientation, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MAG_CAL_REPORT_new_orientation, tvbrange, value) + tvbrange = padded(offset + 50, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MAG_CAL_REPORT_scale_factor, tvbrange, value) end -- dissect payload of message type EFI_STATUS function payload_fns.payload_225(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 73 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 73) @@ -34340,48 +42864,67 @@ function payload_fns.payload_225(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 64 - subtree, value = tree:add_le(f.EFI_STATUS_health, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.EFI_STATUS_ecu_index, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.EFI_STATUS_rpm, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.EFI_STATUS_fuel_consumed, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.EFI_STATUS_fuel_flow, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.EFI_STATUS_engine_load, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.EFI_STATUS_throttle_position, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.EFI_STATUS_spark_dwell_time, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.EFI_STATUS_barometric_pressure, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.EFI_STATUS_intake_manifold_pressure, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.EFI_STATUS_intake_manifold_temperature, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.EFI_STATUS_cylinder_head_temperature, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.EFI_STATUS_ignition_timing, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.EFI_STATUS_injection_time, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.EFI_STATUS_exhaust_gas_temperature, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.EFI_STATUS_throttle_out, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.EFI_STATUS_pt_compensation, padded(field_offset, 4)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.EFI_STATUS_ignition_voltage, padded(field_offset, 4)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.EFI_STATUS_fuel_pressure, padded(field_offset, 4)) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.EFI_STATUS_health, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_ecu_index, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_rpm, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_fuel_consumed, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_fuel_flow, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_engine_load, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_throttle_position, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_spark_dwell_time, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_barometric_pressure, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_intake_manifold_pressure, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_intake_manifold_temperature, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_cylinder_head_temperature, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_ignition_timing, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_injection_time, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_exhaust_gas_temperature, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_throttle_out, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_pt_compensation, tvbrange, value) + tvbrange = padded(offset + 65, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_ignition_voltage, tvbrange, value) + tvbrange = padded(offset + 69, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.EFI_STATUS_fuel_pressure, tvbrange, value) end -- dissect payload of message type ESTIMATOR_STATUS function payload_fns.payload_230(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -34389,31 +42932,41 @@ function payload_fns.payload_230(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_time_usec, padded(field_offset, 8)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_flags, padded(field_offset, 2)) - dissect_flags_ESTIMATOR_STATUS_FLAGS(subtree, "ESTIMATOR_STATUS_flags", value) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_vel_ratio, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_pos_horiz_ratio, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_pos_vert_ratio, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_mag_ratio, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_hagl_ratio, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_tas_ratio, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_pos_horiz_accuracy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ESTIMATOR_STATUS_pos_vert_accuracy, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ESTIMATOR_STATUS_time_usec, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ESTIMATOR_STATUS_flags, tvbrange, value) + dissect_flags_ESTIMATOR_STATUS_FLAGS(subtree, "ESTIMATOR_STATUS_flags", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_vel_ratio, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_pos_horiz_ratio, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_pos_vert_ratio, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_mag_ratio, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_hagl_ratio, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_tas_ratio, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_pos_horiz_accuracy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ESTIMATOR_STATUS_pos_vert_accuracy, tvbrange, value) end -- dissect payload of message type WIND_COV function payload_fns.payload_231(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 40 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 40) @@ -34421,28 +42974,37 @@ function payload_fns.payload_231(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.WIND_COV_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.WIND_COV_wind_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.WIND_COV_wind_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.WIND_COV_wind_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.WIND_COV_var_horiz, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.WIND_COV_var_vert, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.WIND_COV_wind_alt, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.WIND_COV_horiz_accuracy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.WIND_COV_vert_accuracy, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.WIND_COV_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_wind_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_wind_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_wind_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_var_horiz, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_var_vert, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_wind_alt, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_horiz_accuracy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WIND_COV_vert_accuracy, tvbrange, value) end -- dissect payload of message type GPS_INPUT function payload_fns.payload_232(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 65 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 65) @@ -34450,49 +43012,68 @@ function payload_fns.payload_232(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_INPUT_time_usec, padded(field_offset, 8)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.GPS_INPUT_gps_id, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.GPS_INPUT_ignore_flags, padded(field_offset, 2)) - dissect_flags_GPS_INPUT_IGNORE_FLAGS(subtree, "GPS_INPUT_ignore_flags", value) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_INPUT_time_week_ms, padded(field_offset, 4)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.GPS_INPUT_time_week, padded(field_offset, 2)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.GPS_INPUT_fix_type, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_INPUT_lat, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS_INPUT_lon, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS_INPUT_alt, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS_INPUT_hdop, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS_INPUT_vdop, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS_INPUT_vn, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GPS_INPUT_ve, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GPS_INPUT_vd, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GPS_INPUT_speed_accuracy, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GPS_INPUT_horiz_accuracy, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.GPS_INPUT_vert_accuracy, padded(field_offset, 4)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.GPS_INPUT_satellites_visible, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.GPS_INPUT_yaw, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GPS_INPUT_time_usec, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_gps_id, tvbrange, value) + tvbrange = padded(offset + 56, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_ignore_flags, tvbrange, value) + dissect_flags_GPS_INPUT_IGNORE_FLAGS(subtree, "GPS_INPUT_ignore_flags", tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_time_week_ms, tvbrange, value) + tvbrange = padded(offset + 58, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_time_week, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_fix_type, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_INPUT_lat, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GPS_INPUT_lon, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_alt, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_hdop, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_vdop, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_vn, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_ve, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_vd, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_speed_accuracy, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_horiz_accuracy, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GPS_INPUT_vert_accuracy, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_satellites_visible, tvbrange, value) + tvbrange = padded(offset + 63, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_INPUT_yaw, tvbrange, value) end -- dissect payload of message type GPS_RTCM_DATA function payload_fns.payload_233(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 182 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 182) @@ -34500,374 +43081,556 @@ function payload_fns.payload_233(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_flags, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_len, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_20, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_21, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_22, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_23, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_24, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_25, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_26, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_27, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_28, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_29, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_30, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_31, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_32, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_33, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_34, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_35, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_36, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_37, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_38, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_39, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_40, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_41, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_42, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_43, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_44, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_45, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_46, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_47, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_48, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_49, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_50, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_51, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_52, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_53, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_54, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_55, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_56, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_57, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_58, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_59, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_60, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_61, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_62, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_63, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_64, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_65, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_66, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_67, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_68, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_69, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_70, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_71, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_72, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_73, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_74, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_75, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_76, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_77, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_78, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_79, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_80, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_81, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_82, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_83, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_84, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_85, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_86, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_87, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_88, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_89, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_90, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_91, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_92, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_93, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_94, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_95, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_96, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_97, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_98, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_99, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_100, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_101, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_102, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_103, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_104, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_105, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_106, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_107, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_108, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_109, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_110, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_111, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_112, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_113, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_114, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_115, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_116, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_117, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_118, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_119, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_120, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_121, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_122, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_123, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_124, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_125, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_126, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_127, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_128, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_129, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_130, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_131, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_132, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_133, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_134, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_135, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_136, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_137, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_138, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_139, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_140, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_141, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_142, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_143, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_144, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_145, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_146, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_147, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_148, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_149, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_150, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_151, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_152, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_153, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_154, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_155, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_156, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_157, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_158, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_159, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_160, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_161, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_162, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_163, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_164, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_165, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_166, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_167, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_168, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_169, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_170, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_171, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_172, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_173, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_174, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_175, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_176, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_177, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_178, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.GPS_RTCM_DATA_data_179, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_flags, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_len, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_20, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_21, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_22, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_23, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_24, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_25, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_26, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_27, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_28, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_29, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_30, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_31, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_32, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_33, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_34, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_35, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_36, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_37, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_38, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_39, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_40, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_41, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_42, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_43, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_44, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_45, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_46, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_47, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_48, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_49, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_50, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_51, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_52, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_53, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_54, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_55, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_56, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_57, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_58, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_59, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_60, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_61, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_62, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_63, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_64, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_65, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_66, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_67, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_68, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_69, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_70, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_71, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_72, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_73, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_74, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_75, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_76, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_77, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_78, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_79, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_80, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_81, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_82, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_83, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_84, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_85, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_86, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_87, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_88, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_89, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_90, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_91, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_92, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_93, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_94, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_95, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_96, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_97, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_98, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_99, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_100, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_101, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_102, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_103, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_104, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_105, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_106, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_107, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_108, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_109, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_110, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_111, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_112, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_113, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_114, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_115, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_116, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_117, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_118, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_119, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_120, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_121, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_122, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_123, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_124, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_125, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_126, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_127, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_128, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_129, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_130, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_131, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_132, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_133, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_134, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_135, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_136, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_137, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_138, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_139, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_140, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_141, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_142, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_143, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_144, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_145, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_146, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_147, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_148, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_149, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_150, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_151, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_152, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_153, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_154, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_155, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_156, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_157, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_158, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_159, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_160, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_161, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_162, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_163, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_164, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_165, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_166, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_167, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_168, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_169, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_170, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_171, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_172, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_173, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_174, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_175, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_176, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_177, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_178, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RTCM_DATA_data_179, tvbrange, value) end -- dissect payload of message type HIGH_LATENCY function payload_fns.payload_234(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 40 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 40) @@ -34875,59 +43638,83 @@ function payload_fns.payload_234(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 26 - subtree, value = tree:add_le(f.HIGH_LATENCY_base_mode, padded(field_offset, 1)) - dissect_flags_MAV_MODE_FLAG(subtree, "HIGH_LATENCY_base_mode", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIGH_LATENCY_custom_mode, padded(field_offset, 4)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.HIGH_LATENCY_landed_state, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIGH_LATENCY_roll, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.HIGH_LATENCY_pitch, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIGH_LATENCY_heading, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIGH_LATENCY_throttle, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.HIGH_LATENCY_heading_sp, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.HIGH_LATENCY_latitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIGH_LATENCY_longitude, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIGH_LATENCY_altitude_amsl, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.HIGH_LATENCY_altitude_sp, padded(field_offset, 2)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.HIGH_LATENCY_airspeed, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.HIGH_LATENCY_airspeed_sp, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.HIGH_LATENCY_groundspeed, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIGH_LATENCY_climb_rate, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.HIGH_LATENCY_gps_nsat, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.HIGH_LATENCY_gps_fix_type, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.HIGH_LATENCY_battery_remaining, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIGH_LATENCY_temperature, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.HIGH_LATENCY_temperature_air, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.HIGH_LATENCY_failsafe, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.HIGH_LATENCY_wp_num, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIGH_LATENCY_wp_distance, padded(field_offset, 2)) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_base_mode, tvbrange, value) + dissect_flags_MAV_MODE_FLAG(subtree, "HIGH_LATENCY_base_mode", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_custom_mode, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_landed_state, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_roll, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_pitch, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_heading, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_throttle, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_heading_sp, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_latitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_longitude, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_altitude_amsl, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_altitude_sp, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_airspeed, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_airspeed_sp, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_groundspeed, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_climb_rate, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_gps_nsat, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_gps_fix_type, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_battery_remaining, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_temperature, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY_temperature_air, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_failsafe, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_wp_num, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY_wp_distance, tvbrange, value) end -- dissect payload of message type HIGH_LATENCY2 function payload_fns.payload_235(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -34935,65 +43722,92 @@ function payload_fns.payload_235(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HIGH_LATENCY2_timestamp, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HIGH_LATENCY2_type, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.HIGH_LATENCY2_autopilot, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HIGH_LATENCY2_custom_mode, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.HIGH_LATENCY2_latitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HIGH_LATENCY2_longitude, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.HIGH_LATENCY2_altitude, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HIGH_LATENCY2_target_altitude, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.HIGH_LATENCY2_heading, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.HIGH_LATENCY2_target_heading, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.HIGH_LATENCY2_target_distance, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HIGH_LATENCY2_throttle, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.HIGH_LATENCY2_airspeed, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.HIGH_LATENCY2_airspeed_sp, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.HIGH_LATENCY2_groundspeed, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HIGH_LATENCY2_windspeed, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.HIGH_LATENCY2_wind_heading, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.HIGH_LATENCY2_eph, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.HIGH_LATENCY2_epv, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HIGH_LATENCY2_temperature_air, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.HIGH_LATENCY2_climb_rate, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.HIGH_LATENCY2_battery, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HIGH_LATENCY2_wp_num, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.HIGH_LATENCY2_failure_flags, padded(field_offset, 2)) - dissect_flags_HL_FAILURE_FLAG(subtree, "HIGH_LATENCY2_failure_flags", value) - field_offset = offset + 39 - subtree, value = tree:add_le(f.HIGH_LATENCY2_custom0, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HIGH_LATENCY2_custom1, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.HIGH_LATENCY2_custom2, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_timestamp, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_type, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_autopilot, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_custom_mode, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_latitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_longitude, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_altitude, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_target_altitude, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_heading, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_target_heading, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_target_distance, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_throttle, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_airspeed, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_airspeed_sp, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_groundspeed, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_windspeed, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_wind_heading, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_eph, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_epv, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_temperature_air, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_climb_rate, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_battery, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_wp_num, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HIGH_LATENCY2_failure_flags, tvbrange, value) + dissect_flags_HL_FAILURE_FLAG(subtree, "HIGH_LATENCY2_failure_flags", tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_custom0, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_custom1, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.HIGH_LATENCY2_custom2, tvbrange, value) end -- dissect payload of message type VIBRATION function payload_fns.payload_241(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 32 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 32) @@ -35001,24 +43815,31 @@ function payload_fns.payload_241(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.VIBRATION_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VIBRATION_vibration_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VIBRATION_vibration_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VIBRATION_vibration_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.VIBRATION_clipping_0, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.VIBRATION_clipping_1, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.VIBRATION_clipping_2, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.VIBRATION_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VIBRATION_vibration_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VIBRATION_vibration_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VIBRATION_vibration_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIBRATION_clipping_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIBRATION_clipping_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIBRATION_clipping_2, tvbrange, value) end -- dissect payload of message type HOME_POSITION function payload_fns.payload_242(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 60 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 60) @@ -35026,38 +43847,52 @@ function payload_fns.payload_242(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.HOME_POSITION_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.HOME_POSITION_longitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HOME_POSITION_altitude, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HOME_POSITION_x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HOME_POSITION_y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.HOME_POSITION_z, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.HOME_POSITION_q_0, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.HOME_POSITION_q_1, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.HOME_POSITION_q_2, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.HOME_POSITION_q_3, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.HOME_POSITION_approach_x, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.HOME_POSITION_approach_y, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.HOME_POSITION_approach_z, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.HOME_POSITION_time_usec, padded(field_offset, 8)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HOME_POSITION_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HOME_POSITION_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.HOME_POSITION_altitude, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_z, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_q_0, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_q_1, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_q_2, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_q_3, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_approach_x, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_approach_y, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HOME_POSITION_approach_z, tvbrange, value) + tvbrange = padded(offset + 52, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.HOME_POSITION_time_usec, tvbrange, value) end -- dissect payload of message type SET_HOME_POSITION function payload_fns.payload_243(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 61 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 61) @@ -35065,40 +43900,55 @@ function payload_fns.payload_243(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 52 - subtree, value = tree:add_le(f.SET_HOME_POSITION_target_system, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SET_HOME_POSITION_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SET_HOME_POSITION_longitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SET_HOME_POSITION_altitude, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SET_HOME_POSITION_x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SET_HOME_POSITION_y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SET_HOME_POSITION_z, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SET_HOME_POSITION_q_0, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SET_HOME_POSITION_q_1, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SET_HOME_POSITION_q_2, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SET_HOME_POSITION_q_3, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SET_HOME_POSITION_approach_x, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.SET_HOME_POSITION_approach_y, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.SET_HOME_POSITION_approach_z, padded(field_offset, 4)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.SET_HOME_POSITION_time_usec, padded(field_offset, 8)) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SET_HOME_POSITION_target_system, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_HOME_POSITION_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_HOME_POSITION_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SET_HOME_POSITION_altitude, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_z, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_q_0, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_q_1, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_q_2, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_q_3, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_approach_x, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_approach_y, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.SET_HOME_POSITION_approach_z, tvbrange, value) + tvbrange = padded(offset + 53, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SET_HOME_POSITION_time_usec, tvbrange, value) end -- dissect payload of message type MESSAGE_INTERVAL function payload_fns.payload_244(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -35106,14 +43956,16 @@ function payload_fns.payload_244(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.MESSAGE_INTERVAL_message_id, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.MESSAGE_INTERVAL_interval_us, padded(field_offset, 4)) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MESSAGE_INTERVAL_message_id, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.MESSAGE_INTERVAL_interval_us, tvbrange, value) end -- dissect payload of message type EXTENDED_SYS_STATE function payload_fns.payload_245(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -35121,14 +43973,16 @@ function payload_fns.payload_245(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.EXTENDED_SYS_STATE_vtol_state, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.EXTENDED_SYS_STATE_landed_state, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.EXTENDED_SYS_STATE_vtol_state, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.EXTENDED_SYS_STATE_landed_state, tvbrange, value) end -- dissect payload of message type ADSB_VEHICLE function payload_fns.payload_246(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 38 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 38) @@ -35136,37 +43990,50 @@ function payload_fns.payload_246(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ADSB_VEHICLE_ICAO_address, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ADSB_VEHICLE_lat, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ADSB_VEHICLE_lon, padded(field_offset, 4)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.ADSB_VEHICLE_altitude_type, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ADSB_VEHICLE_altitude, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ADSB_VEHICLE_heading, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ADSB_VEHICLE_hor_velocity, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ADSB_VEHICLE_ver_velocity, padded(field_offset, 2)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.ADSB_VEHICLE_callsign, padded(field_offset, 9)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ADSB_VEHICLE_emitter_type, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.ADSB_VEHICLE_tslc, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ADSB_VEHICLE_flags, padded(field_offset, 2)) - dissect_flags_ADSB_FLAGS(subtree, "ADSB_VEHICLE_flags", value) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ADSB_VEHICLE_squawk, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_ICAO_address, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ADSB_VEHICLE_lat, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ADSB_VEHICLE_lon, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_altitude_type, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.ADSB_VEHICLE_altitude, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_heading, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_hor_velocity, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.ADSB_VEHICLE_ver_velocity, tvbrange, value) + tvbrange = padded(offset + 27, 9) + value = tvbrange:string() + subtree = tree:add_le(f.ADSB_VEHICLE_callsign, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_emitter_type, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_tslc, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_flags, tvbrange, value) + dissect_flags_ADSB_FLAGS(subtree, "ADSB_VEHICLE_flags", tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ADSB_VEHICLE_squawk, tvbrange, value) end -- dissect payload of message type COLLISION function payload_fns.payload_247(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 19 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 19) @@ -35174,24 +44041,31 @@ function payload_fns.payload_247(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 16 - subtree, value = tree:add_le(f.COLLISION_src, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.COLLISION_id, padded(field_offset, 4)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.COLLISION_action, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.COLLISION_threat_level, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.COLLISION_time_to_minimum_delta, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.COLLISION_altitude_minimum_delta, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.COLLISION_horizontal_minimum_delta, padded(field_offset, 4)) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COLLISION_src, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COLLISION_id, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COLLISION_action, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.COLLISION_threat_level, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COLLISION_time_to_minimum_delta, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COLLISION_altitude_minimum_delta, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.COLLISION_horizontal_minimum_delta, tvbrange, value) end -- dissect payload of message type V2_EXTENSION function payload_fns.payload_248(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 254 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 254) @@ -35199,516 +44073,769 @@ function payload_fns.payload_248(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.V2_EXTENSION_target_network, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.V2_EXTENSION_target_system, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.V2_EXTENSION_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.V2_EXTENSION_message_type, padded(field_offset, 2)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_0, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_1, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_2, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_3, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_4, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_5, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_6, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_7, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_8, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_9, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_10, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_11, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_12, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_13, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_14, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_15, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_16, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_17, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_18, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_19, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_20, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_21, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_22, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_23, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_24, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_25, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_26, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_27, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_28, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_29, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_30, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_31, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_32, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_33, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_34, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_35, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_36, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_37, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_38, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_39, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_40, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_41, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_42, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_43, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_44, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_45, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_46, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_47, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_48, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_49, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_50, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_51, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_52, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_53, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_54, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_55, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_56, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_57, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_58, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_59, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_60, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_61, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_62, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_63, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_64, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_65, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_66, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_67, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_68, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_69, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_70, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_71, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_72, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_73, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_74, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_75, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_76, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_77, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_78, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_79, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_80, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_81, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_82, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_83, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_84, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_85, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_86, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_87, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_88, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_89, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_90, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_91, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_92, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_93, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_94, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_95, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_96, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_97, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_98, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_99, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_100, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_101, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_102, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_103, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_104, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_105, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_106, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_107, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_108, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_109, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_110, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_111, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_112, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_113, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_114, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_115, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_116, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_117, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_118, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_119, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_120, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_121, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_122, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_123, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_124, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_125, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_126, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_127, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_128, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_129, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_130, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_131, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_132, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_133, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_134, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_135, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_136, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_137, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_138, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_139, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_140, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_141, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_142, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_143, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_144, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_145, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_146, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_147, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_148, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_149, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_150, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_151, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_152, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_153, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_154, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_155, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_156, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_157, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_158, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_159, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_160, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_161, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_162, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_163, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_164, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_165, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_166, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_167, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_168, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_169, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_170, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_171, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_172, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_173, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_174, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_175, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_176, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_177, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_178, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_179, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_180, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_181, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_182, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_183, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_184, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_185, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_186, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_187, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_188, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_189, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_190, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_191, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_192, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_193, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_194, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_195, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_196, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_197, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_198, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_199, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_200, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_201, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_202, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_203, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_204, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_205, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_206, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_207, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_208, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_209, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_210, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_211, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_212, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_213, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_214, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_215, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_216, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_217, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_218, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_219, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_220, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_221, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_222, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_223, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_224, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_225, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_226, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_227, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_228, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_229, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_230, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_231, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_232, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_233, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_234, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_235, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_236, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_237, padded(field_offset, 1)) - field_offset = offset + 243 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_238, padded(field_offset, 1)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_239, padded(field_offset, 1)) - field_offset = offset + 245 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_240, padded(field_offset, 1)) - field_offset = offset + 246 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_241, padded(field_offset, 1)) - field_offset = offset + 247 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_242, padded(field_offset, 1)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_243, padded(field_offset, 1)) - field_offset = offset + 249 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_244, padded(field_offset, 1)) - field_offset = offset + 250 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_245, padded(field_offset, 1)) - field_offset = offset + 251 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_246, padded(field_offset, 1)) - field_offset = offset + 252 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_247, padded(field_offset, 1)) - field_offset = offset + 253 - subtree, value = tree:add_le(f.V2_EXTENSION_payload_248, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_target_network, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_target_system, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_message_type, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_0, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_1, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_2, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_3, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_4, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_5, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_6, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_7, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_8, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_9, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_10, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_11, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_12, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_13, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_14, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_15, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_16, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_17, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_18, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_19, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_20, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_21, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_22, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_23, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_24, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_25, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_26, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_27, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_28, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_29, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_30, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_31, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_32, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_33, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_34, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_35, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_36, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_37, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_38, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_39, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_40, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_41, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_42, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_43, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_44, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_45, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_46, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_47, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_48, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_49, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_50, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_51, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_52, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_53, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_54, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_55, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_56, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_57, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_58, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_59, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_60, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_61, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_62, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_63, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_64, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_65, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_66, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_67, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_68, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_69, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_70, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_71, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_72, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_73, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_74, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_75, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_76, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_77, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_78, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_79, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_80, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_81, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_82, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_83, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_84, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_85, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_86, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_87, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_88, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_89, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_90, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_91, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_92, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_93, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_94, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_95, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_96, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_97, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_98, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_99, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_100, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_101, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_102, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_103, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_104, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_105, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_106, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_107, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_108, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_109, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_110, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_111, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_112, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_113, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_114, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_115, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_116, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_117, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_118, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_119, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_120, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_121, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_122, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_123, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_124, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_125, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_126, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_127, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_128, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_129, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_130, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_131, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_132, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_133, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_134, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_135, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_136, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_137, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_138, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_139, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_140, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_141, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_142, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_143, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_144, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_145, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_146, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_147, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_148, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_149, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_150, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_151, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_152, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_153, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_154, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_155, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_156, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_157, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_158, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_159, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_160, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_161, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_162, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_163, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_164, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_165, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_166, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_167, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_168, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_169, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_170, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_171, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_172, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_173, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_174, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_175, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_176, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_177, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_178, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_179, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_180, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_181, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_182, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_183, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_184, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_185, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_186, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_187, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_188, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_189, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_190, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_191, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_192, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_193, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_194, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_195, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_196, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_197, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_198, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_199, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_200, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_201, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_202, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_203, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_204, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_205, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_206, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_207, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_208, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_209, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_210, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_211, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_212, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_213, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_214, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_215, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_216, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_217, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_218, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_219, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_220, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_221, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_222, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_223, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_224, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_225, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_226, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_227, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_228, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_229, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_230, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_231, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_232, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_233, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_234, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_235, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_236, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_237, tvbrange, value) + tvbrange = padded(offset + 243, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_238, tvbrange, value) + tvbrange = padded(offset + 244, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_239, tvbrange, value) + tvbrange = padded(offset + 245, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_240, tvbrange, value) + tvbrange = padded(offset + 246, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_241, tvbrange, value) + tvbrange = padded(offset + 247, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_242, tvbrange, value) + tvbrange = padded(offset + 248, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_243, tvbrange, value) + tvbrange = padded(offset + 249, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_244, tvbrange, value) + tvbrange = padded(offset + 250, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_245, tvbrange, value) + tvbrange = padded(offset + 251, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_246, tvbrange, value) + tvbrange = padded(offset + 252, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_247, tvbrange, value) + tvbrange = padded(offset + 253, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.V2_EXTENSION_payload_248, tvbrange, value) end -- dissect payload of message type MEMORY_VECT function payload_fns.payload_249(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 36 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 36) @@ -35716,80 +44843,115 @@ function payload_fns.payload_249(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MEMORY_VECT_address, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.MEMORY_VECT_ver, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.MEMORY_VECT_type, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MEMORY_VECT_value_0, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.MEMORY_VECT_value_1, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.MEMORY_VECT_value_2, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.MEMORY_VECT_value_3, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MEMORY_VECT_value_4, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.MEMORY_VECT_value_5, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.MEMORY_VECT_value_6, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.MEMORY_VECT_value_7, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.MEMORY_VECT_value_8, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.MEMORY_VECT_value_9, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.MEMORY_VECT_value_10, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.MEMORY_VECT_value_11, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MEMORY_VECT_value_12, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.MEMORY_VECT_value_13, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.MEMORY_VECT_value_14, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.MEMORY_VECT_value_15, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.MEMORY_VECT_value_16, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.MEMORY_VECT_value_17, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.MEMORY_VECT_value_18, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.MEMORY_VECT_value_19, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.MEMORY_VECT_value_20, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.MEMORY_VECT_value_21, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.MEMORY_VECT_value_22, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.MEMORY_VECT_value_23, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.MEMORY_VECT_value_24, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.MEMORY_VECT_value_25, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.MEMORY_VECT_value_26, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.MEMORY_VECT_value_27, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.MEMORY_VECT_value_28, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.MEMORY_VECT_value_29, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.MEMORY_VECT_value_30, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.MEMORY_VECT_value_31, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MEMORY_VECT_address, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MEMORY_VECT_ver, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MEMORY_VECT_type, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_0, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_1, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_2, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_3, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_4, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_5, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_6, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_7, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_8, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_9, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_10, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_11, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_12, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_13, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_14, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_15, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_16, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_17, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_18, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_19, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_20, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_21, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_22, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_23, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_24, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_25, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_26, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_27, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_28, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_29, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_30, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.MEMORY_VECT_value_31, tvbrange, value) end -- dissect payload of message type DEBUG_VECT function payload_fns.payload_250(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 30 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 30) @@ -35797,20 +44959,25 @@ function payload_fns.payload_250(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 20 - subtree, value = tree:add_le(f.DEBUG_VECT_name, padded(field_offset, 10)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEBUG_VECT_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEBUG_VECT_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.DEBUG_VECT_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.DEBUG_VECT_z, padded(field_offset, 4)) + tvbrange = padded(offset + 20, 10) + value = tvbrange:string() + subtree = tree:add_le(f.DEBUG_VECT_name, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.DEBUG_VECT_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_VECT_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_VECT_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_VECT_z, tvbrange, value) end -- dissect payload of message type NAMED_VALUE_FLOAT function payload_fns.payload_251(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 18 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 18) @@ -35818,16 +44985,19 @@ function payload_fns.payload_251(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.NAMED_VALUE_FLOAT_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.NAMED_VALUE_FLOAT_name, padded(field_offset, 10)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.NAMED_VALUE_FLOAT_value, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.NAMED_VALUE_FLOAT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 8, 10) + value = tvbrange:string() + subtree = tree:add_le(f.NAMED_VALUE_FLOAT_name, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.NAMED_VALUE_FLOAT_value, tvbrange, value) end -- dissect payload of message type NAMED_VALUE_INT function payload_fns.payload_252(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 18 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 18) @@ -35835,16 +45005,19 @@ function payload_fns.payload_252(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.NAMED_VALUE_INT_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.NAMED_VALUE_INT_name, padded(field_offset, 10)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.NAMED_VALUE_INT_value, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.NAMED_VALUE_INT_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 8, 10) + value = tvbrange:string() + subtree = tree:add_le(f.NAMED_VALUE_INT_name, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.NAMED_VALUE_INT_value, tvbrange, value) end -- dissect payload of message type STATUSTEXT function payload_fns.payload_253(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 54 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 54) @@ -35852,18 +45025,22 @@ function payload_fns.payload_253(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.STATUSTEXT_severity, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.STATUSTEXT_text, padded(field_offset, 50)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.STATUSTEXT_id, padded(field_offset, 2)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.STATUSTEXT_chunk_seq, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STATUSTEXT_severity, tvbrange, value) + tvbrange = padded(offset + 1, 50) + value = tvbrange:string() + subtree = tree:add_le(f.STATUSTEXT_text, tvbrange, value) + tvbrange = padded(offset + 51, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STATUSTEXT_id, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STATUSTEXT_chunk_seq, tvbrange, value) end -- dissect payload of message type DEBUG function payload_fns.payload_254(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -35871,16 +45048,19 @@ function payload_fns.payload_254(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEBUG_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEBUG_ind, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.DEBUG_value, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEBUG_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEBUG_ind, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_value, tvbrange, value) end -- dissect payload of message type SETUP_SIGNING function payload_fns.payload_256(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -35888,80 +45068,115 @@ function payload_fns.payload_256(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.SETUP_SIGNING_target_system, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.SETUP_SIGNING_target_component, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_0, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_1, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_2, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_3, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_4, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_5, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_6, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_7, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_8, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_9, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_10, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_11, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_12, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_13, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_14, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_15, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_16, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_17, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_18, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_19, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_20, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_21, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_22, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_23, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_24, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_25, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_26, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_27, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_28, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_29, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_30, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.SETUP_SIGNING_secret_key_31, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SETUP_SIGNING_initial_timestamp, padded(field_offset, 8)) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_target_component, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_0, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_1, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_2, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_3, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_4, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_5, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_6, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_7, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_8, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_9, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_10, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_11, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_12, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_13, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_14, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_15, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_16, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_17, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_18, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_19, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_20, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_21, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_22, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_23, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_24, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_25, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_26, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_27, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_28, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_29, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_30, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SETUP_SIGNING_secret_key_31, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.SETUP_SIGNING_initial_timestamp, tvbrange, value) end -- dissect payload of message type BUTTON_CHANGE function payload_fns.payload_257(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -35969,16 +45184,19 @@ function payload_fns.payload_257(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.BUTTON_CHANGE_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.BUTTON_CHANGE_last_change_ms, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.BUTTON_CHANGE_state, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BUTTON_CHANGE_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BUTTON_CHANGE_last_change_ms, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.BUTTON_CHANGE_state, tvbrange, value) end -- dissect payload of message type PLAY_TUNE function payload_fns.payload_258(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 232 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 232) @@ -35986,18 +45204,22 @@ function payload_fns.payload_258(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.PLAY_TUNE_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.PLAY_TUNE_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.PLAY_TUNE_tune, padded(field_offset, 30)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.PLAY_TUNE_tune2, padded(field_offset, 200)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PLAY_TUNE_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PLAY_TUNE_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 30) + value = tvbrange:string() + subtree = tree:add_le(f.PLAY_TUNE_tune, tvbrange, value) + tvbrange = padded(offset + 32, 200) + value = tvbrange:string() + subtree = tree:add_le(f.PLAY_TUNE_tune2, tvbrange, value) end -- dissect payload of message type CAMERA_INFORMATION function payload_fns.payload_259(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 235 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 235) @@ -36005,161 +45227,236 @@ function payload_fns.payload_259(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_0, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_1, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_2, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_3, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_4, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_5, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_6, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_7, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_8, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_9, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_10, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_11, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_12, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_13, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_14, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_15, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_16, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_17, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_18, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_19, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_20, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_21, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_22, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_23, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_24, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_25, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_26, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_27, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_28, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_29, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_30, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_vendor_name_31, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_0, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_1, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_2, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_3, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_4, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_5, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_6, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_7, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_8, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_9, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_10, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_11, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_12, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_13, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_14, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_15, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_16, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_17, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_18, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_19, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_20, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_21, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_22, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_23, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_24, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_25, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_26, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_27, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_28, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_29, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_30, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_model_name_31, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_firmware_version, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_focal_length, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_sensor_size_h, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_sensor_size_v, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_resolution_h, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_resolution_v, padded(field_offset, 2)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_lens_id, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_flags, padded(field_offset, 4)) - dissect_flags_CAMERA_CAP_FLAGS(subtree, "CAMERA_INFORMATION_flags", value) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_cam_definition_version, padded(field_offset, 2)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.CAMERA_INFORMATION_cam_definition_uri, padded(field_offset, 140)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_0, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_1, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_2, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_3, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_4, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_5, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_6, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_7, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_8, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_9, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_10, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_11, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_12, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_13, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_14, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_15, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_16, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_17, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_18, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_19, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_20, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_21, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_22, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_23, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_24, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_25, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_26, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_27, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_28, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_29, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_30, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_vendor_name_31, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_0, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_1, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_2, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_3, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_4, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_5, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_6, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_7, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_8, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_9, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_10, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_11, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_12, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_13, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_14, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_15, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_16, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_17, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_18, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_19, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_20, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_21, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_22, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_23, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_24, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_25, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_26, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_27, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_28, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_29, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_30, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_model_name_31, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_firmware_version, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_INFORMATION_focal_length, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_INFORMATION_sensor_size_h, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_INFORMATION_sensor_size_v, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_resolution_h, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_resolution_v, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_lens_id, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_flags, tvbrange, value) + dissect_flags_CAMERA_CAP_FLAGS(subtree, "CAMERA_INFORMATION_flags", tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_cam_definition_version, tvbrange, value) + tvbrange = padded(offset + 95, 140) + value = tvbrange:string() + subtree = tree:add_le(f.CAMERA_INFORMATION_cam_definition_uri, tvbrange, value) end -- dissect payload of message type CAMERA_SETTINGS function payload_fns.payload_260(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 13 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 13) @@ -36167,18 +45464,22 @@ function payload_fns.payload_260(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_SETTINGS_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAMERA_SETTINGS_mode_id, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.CAMERA_SETTINGS_zoomLevel, padded(field_offset, 4)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.CAMERA_SETTINGS_focusLevel, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_SETTINGS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_SETTINGS_mode_id, tvbrange, value) + tvbrange = padded(offset + 5, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_SETTINGS_zoomLevel, tvbrange, value) + tvbrange = padded(offset + 9, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_SETTINGS_focusLevel, tvbrange, value) end -- dissect payload of message type STORAGE_INFORMATION function payload_fns.payload_261(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 60 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 60) @@ -36186,32 +45487,43 @@ function payload_fns.payload_261(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_storage_id, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_storage_count, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_status, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_total_capacity, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_used_capacity, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_available_capacity, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_read_speed, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_write_speed, padded(field_offset, 4)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_type, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.STORAGE_INFORMATION_name, padded(field_offset, 32)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORAGE_INFORMATION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORAGE_INFORMATION_storage_id, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORAGE_INFORMATION_storage_count, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORAGE_INFORMATION_status, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORAGE_INFORMATION_total_capacity, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORAGE_INFORMATION_used_capacity, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORAGE_INFORMATION_available_capacity, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORAGE_INFORMATION_read_speed, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.STORAGE_INFORMATION_write_speed, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.STORAGE_INFORMATION_type, tvbrange, value) + tvbrange = padded(offset + 28, 32) + value = tvbrange:string() + subtree = tree:add_le(f.STORAGE_INFORMATION_name, tvbrange, value) end -- dissect payload of message type CAMERA_CAPTURE_STATUS function payload_fns.payload_262(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 22 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 22) @@ -36219,24 +45531,31 @@ function payload_fns.payload_262(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_image_status, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_video_status, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_image_interval, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_recording_time_ms, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_available_capacity, padded(field_offset, 4)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.CAMERA_CAPTURE_STATUS_image_count, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_image_status, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_video_status, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_image_interval, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_recording_time_ms, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_available_capacity, tvbrange, value) + tvbrange = padded(offset + 18, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_CAPTURE_STATUS_image_count, tvbrange, value) end -- dissect payload of message type CAMERA_IMAGE_CAPTURED function payload_fns.payload_263(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 255 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 255) @@ -36244,38 +45563,52 @@ function payload_fns.payload_263(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_time_utc, padded(field_offset, 8)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_camera_id, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_lat, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_lon, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_alt, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_relative_alt, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_0, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_1, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_2, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_3, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_image_index, padded(field_offset, 4)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_capture_result, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.CAMERA_IMAGE_CAPTURED_file_url, padded(field_offset, 205)) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_time_utc, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_camera_id, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_lat, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_lon, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_alt, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_relative_alt, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_2, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_q_3, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_image_index, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_capture_result, tvbrange, value) + tvbrange = padded(offset + 50, 205) + value = tvbrange:string() + subtree = tree:add_le(f.CAMERA_IMAGE_CAPTURED_file_url, tvbrange, value) end -- dissect payload of message type FLIGHT_INFORMATION function payload_fns.payload_264(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 28 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 28) @@ -36283,18 +45616,22 @@ function payload_fns.payload_264(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 24 - subtree, value = tree:add_le(f.FLIGHT_INFORMATION_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.FLIGHT_INFORMATION_arming_time_utc, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.FLIGHT_INFORMATION_takeoff_time_utc, padded(field_offset, 8)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.FLIGHT_INFORMATION_flight_uuid, padded(field_offset, 8)) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.FLIGHT_INFORMATION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FLIGHT_INFORMATION_arming_time_utc, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FLIGHT_INFORMATION_takeoff_time_utc, tvbrange, value) + tvbrange = padded(offset + 16, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.FLIGHT_INFORMATION_flight_uuid, tvbrange, value) end -- dissect payload of message type MOUNT_ORIENTATION function payload_fns.payload_265(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -36302,20 +45639,25 @@ function payload_fns.payload_265(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.MOUNT_ORIENTATION_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.MOUNT_ORIENTATION_roll, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.MOUNT_ORIENTATION_pitch, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.MOUNT_ORIENTATION_yaw, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.MOUNT_ORIENTATION_yaw_absolute, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.MOUNT_ORIENTATION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MOUNT_ORIENTATION_roll, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MOUNT_ORIENTATION_pitch, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MOUNT_ORIENTATION_yaw, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.MOUNT_ORIENTATION_yaw_absolute, tvbrange, value) end -- dissect payload of message type LOGGING_DATA function payload_fns.payload_266(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 255 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 255) @@ -36323,518 +45665,772 @@ function payload_fns.payload_266(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.LOGGING_DATA_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.LOGGING_DATA_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOGGING_DATA_sequence, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOGGING_DATA_length, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.LOGGING_DATA_first_message_offset, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.LOGGING_DATA_data_0, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.LOGGING_DATA_data_1, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOGGING_DATA_data_2, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.LOGGING_DATA_data_3, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.LOGGING_DATA_data_4, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.LOGGING_DATA_data_5, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOGGING_DATA_data_6, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.LOGGING_DATA_data_7, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.LOGGING_DATA_data_8, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.LOGGING_DATA_data_9, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOGGING_DATA_data_10, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.LOGGING_DATA_data_11, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.LOGGING_DATA_data_12, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.LOGGING_DATA_data_13, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOGGING_DATA_data_14, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.LOGGING_DATA_data_15, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.LOGGING_DATA_data_16, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.LOGGING_DATA_data_17, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOGGING_DATA_data_18, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.LOGGING_DATA_data_19, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.LOGGING_DATA_data_20, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.LOGGING_DATA_data_21, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LOGGING_DATA_data_22, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.LOGGING_DATA_data_23, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.LOGGING_DATA_data_24, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.LOGGING_DATA_data_25, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.LOGGING_DATA_data_26, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.LOGGING_DATA_data_27, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.LOGGING_DATA_data_28, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.LOGGING_DATA_data_29, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.LOGGING_DATA_data_30, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.LOGGING_DATA_data_31, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.LOGGING_DATA_data_32, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.LOGGING_DATA_data_33, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.LOGGING_DATA_data_34, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.LOGGING_DATA_data_35, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.LOGGING_DATA_data_36, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.LOGGING_DATA_data_37, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.LOGGING_DATA_data_38, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.LOGGING_DATA_data_39, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.LOGGING_DATA_data_40, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.LOGGING_DATA_data_41, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.LOGGING_DATA_data_42, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.LOGGING_DATA_data_43, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.LOGGING_DATA_data_44, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.LOGGING_DATA_data_45, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.LOGGING_DATA_data_46, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.LOGGING_DATA_data_47, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.LOGGING_DATA_data_48, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.LOGGING_DATA_data_49, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.LOGGING_DATA_data_50, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.LOGGING_DATA_data_51, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.LOGGING_DATA_data_52, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.LOGGING_DATA_data_53, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.LOGGING_DATA_data_54, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.LOGGING_DATA_data_55, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.LOGGING_DATA_data_56, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.LOGGING_DATA_data_57, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.LOGGING_DATA_data_58, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.LOGGING_DATA_data_59, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.LOGGING_DATA_data_60, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.LOGGING_DATA_data_61, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.LOGGING_DATA_data_62, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.LOGGING_DATA_data_63, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.LOGGING_DATA_data_64, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.LOGGING_DATA_data_65, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.LOGGING_DATA_data_66, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.LOGGING_DATA_data_67, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.LOGGING_DATA_data_68, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.LOGGING_DATA_data_69, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.LOGGING_DATA_data_70, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.LOGGING_DATA_data_71, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.LOGGING_DATA_data_72, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.LOGGING_DATA_data_73, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.LOGGING_DATA_data_74, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.LOGGING_DATA_data_75, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.LOGGING_DATA_data_76, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.LOGGING_DATA_data_77, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.LOGGING_DATA_data_78, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.LOGGING_DATA_data_79, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.LOGGING_DATA_data_80, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.LOGGING_DATA_data_81, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.LOGGING_DATA_data_82, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.LOGGING_DATA_data_83, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.LOGGING_DATA_data_84, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.LOGGING_DATA_data_85, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.LOGGING_DATA_data_86, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.LOGGING_DATA_data_87, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.LOGGING_DATA_data_88, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.LOGGING_DATA_data_89, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.LOGGING_DATA_data_90, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.LOGGING_DATA_data_91, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.LOGGING_DATA_data_92, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.LOGGING_DATA_data_93, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.LOGGING_DATA_data_94, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.LOGGING_DATA_data_95, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.LOGGING_DATA_data_96, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.LOGGING_DATA_data_97, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.LOGGING_DATA_data_98, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.LOGGING_DATA_data_99, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.LOGGING_DATA_data_100, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.LOGGING_DATA_data_101, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.LOGGING_DATA_data_102, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.LOGGING_DATA_data_103, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.LOGGING_DATA_data_104, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.LOGGING_DATA_data_105, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.LOGGING_DATA_data_106, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.LOGGING_DATA_data_107, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.LOGGING_DATA_data_108, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.LOGGING_DATA_data_109, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.LOGGING_DATA_data_110, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.LOGGING_DATA_data_111, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.LOGGING_DATA_data_112, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.LOGGING_DATA_data_113, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.LOGGING_DATA_data_114, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.LOGGING_DATA_data_115, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.LOGGING_DATA_data_116, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.LOGGING_DATA_data_117, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.LOGGING_DATA_data_118, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.LOGGING_DATA_data_119, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.LOGGING_DATA_data_120, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.LOGGING_DATA_data_121, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.LOGGING_DATA_data_122, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.LOGGING_DATA_data_123, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.LOGGING_DATA_data_124, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.LOGGING_DATA_data_125, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.LOGGING_DATA_data_126, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.LOGGING_DATA_data_127, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.LOGGING_DATA_data_128, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.LOGGING_DATA_data_129, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.LOGGING_DATA_data_130, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.LOGGING_DATA_data_131, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.LOGGING_DATA_data_132, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.LOGGING_DATA_data_133, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.LOGGING_DATA_data_134, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.LOGGING_DATA_data_135, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.LOGGING_DATA_data_136, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.LOGGING_DATA_data_137, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.LOGGING_DATA_data_138, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.LOGGING_DATA_data_139, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.LOGGING_DATA_data_140, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.LOGGING_DATA_data_141, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.LOGGING_DATA_data_142, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.LOGGING_DATA_data_143, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.LOGGING_DATA_data_144, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.LOGGING_DATA_data_145, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.LOGGING_DATA_data_146, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.LOGGING_DATA_data_147, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.LOGGING_DATA_data_148, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.LOGGING_DATA_data_149, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.LOGGING_DATA_data_150, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.LOGGING_DATA_data_151, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.LOGGING_DATA_data_152, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.LOGGING_DATA_data_153, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.LOGGING_DATA_data_154, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.LOGGING_DATA_data_155, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.LOGGING_DATA_data_156, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.LOGGING_DATA_data_157, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.LOGGING_DATA_data_158, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.LOGGING_DATA_data_159, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.LOGGING_DATA_data_160, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.LOGGING_DATA_data_161, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.LOGGING_DATA_data_162, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.LOGGING_DATA_data_163, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.LOGGING_DATA_data_164, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.LOGGING_DATA_data_165, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.LOGGING_DATA_data_166, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.LOGGING_DATA_data_167, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.LOGGING_DATA_data_168, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.LOGGING_DATA_data_169, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.LOGGING_DATA_data_170, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.LOGGING_DATA_data_171, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.LOGGING_DATA_data_172, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.LOGGING_DATA_data_173, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.LOGGING_DATA_data_174, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.LOGGING_DATA_data_175, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.LOGGING_DATA_data_176, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.LOGGING_DATA_data_177, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.LOGGING_DATA_data_178, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.LOGGING_DATA_data_179, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.LOGGING_DATA_data_180, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.LOGGING_DATA_data_181, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.LOGGING_DATA_data_182, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.LOGGING_DATA_data_183, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.LOGGING_DATA_data_184, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.LOGGING_DATA_data_185, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.LOGGING_DATA_data_186, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.LOGGING_DATA_data_187, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.LOGGING_DATA_data_188, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.LOGGING_DATA_data_189, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.LOGGING_DATA_data_190, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.LOGGING_DATA_data_191, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.LOGGING_DATA_data_192, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.LOGGING_DATA_data_193, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.LOGGING_DATA_data_194, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.LOGGING_DATA_data_195, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.LOGGING_DATA_data_196, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.LOGGING_DATA_data_197, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.LOGGING_DATA_data_198, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.LOGGING_DATA_data_199, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.LOGGING_DATA_data_200, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.LOGGING_DATA_data_201, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.LOGGING_DATA_data_202, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.LOGGING_DATA_data_203, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.LOGGING_DATA_data_204, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.LOGGING_DATA_data_205, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.LOGGING_DATA_data_206, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.LOGGING_DATA_data_207, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.LOGGING_DATA_data_208, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.LOGGING_DATA_data_209, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.LOGGING_DATA_data_210, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.LOGGING_DATA_data_211, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.LOGGING_DATA_data_212, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.LOGGING_DATA_data_213, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.LOGGING_DATA_data_214, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.LOGGING_DATA_data_215, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.LOGGING_DATA_data_216, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.LOGGING_DATA_data_217, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.LOGGING_DATA_data_218, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.LOGGING_DATA_data_219, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.LOGGING_DATA_data_220, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.LOGGING_DATA_data_221, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.LOGGING_DATA_data_222, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.LOGGING_DATA_data_223, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.LOGGING_DATA_data_224, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.LOGGING_DATA_data_225, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.LOGGING_DATA_data_226, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.LOGGING_DATA_data_227, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.LOGGING_DATA_data_228, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.LOGGING_DATA_data_229, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.LOGGING_DATA_data_230, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.LOGGING_DATA_data_231, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.LOGGING_DATA_data_232, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.LOGGING_DATA_data_233, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.LOGGING_DATA_data_234, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.LOGGING_DATA_data_235, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.LOGGING_DATA_data_236, padded(field_offset, 1)) - field_offset = offset + 243 - subtree, value = tree:add_le(f.LOGGING_DATA_data_237, padded(field_offset, 1)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.LOGGING_DATA_data_238, padded(field_offset, 1)) - field_offset = offset + 245 - subtree, value = tree:add_le(f.LOGGING_DATA_data_239, padded(field_offset, 1)) - field_offset = offset + 246 - subtree, value = tree:add_le(f.LOGGING_DATA_data_240, padded(field_offset, 1)) - field_offset = offset + 247 - subtree, value = tree:add_le(f.LOGGING_DATA_data_241, padded(field_offset, 1)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.LOGGING_DATA_data_242, padded(field_offset, 1)) - field_offset = offset + 249 - subtree, value = tree:add_le(f.LOGGING_DATA_data_243, padded(field_offset, 1)) - field_offset = offset + 250 - subtree, value = tree:add_le(f.LOGGING_DATA_data_244, padded(field_offset, 1)) - field_offset = offset + 251 - subtree, value = tree:add_le(f.LOGGING_DATA_data_245, padded(field_offset, 1)) - field_offset = offset + 252 - subtree, value = tree:add_le(f.LOGGING_DATA_data_246, padded(field_offset, 1)) - field_offset = offset + 253 - subtree, value = tree:add_le(f.LOGGING_DATA_data_247, padded(field_offset, 1)) - field_offset = offset + 254 - subtree, value = tree:add_le(f.LOGGING_DATA_data_248, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_sequence, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_length, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_first_message_offset, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_0, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_1, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_2, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_3, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_4, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_5, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_6, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_7, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_8, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_9, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_10, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_11, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_12, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_13, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_14, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_15, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_16, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_17, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_18, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_19, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_20, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_21, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_22, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_23, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_24, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_25, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_26, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_27, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_28, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_29, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_30, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_31, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_32, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_33, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_34, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_35, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_36, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_37, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_38, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_39, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_40, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_41, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_42, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_43, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_44, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_45, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_46, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_47, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_48, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_49, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_50, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_51, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_52, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_53, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_54, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_55, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_56, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_57, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_58, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_59, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_60, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_61, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_62, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_63, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_64, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_65, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_66, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_67, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_68, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_69, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_70, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_71, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_72, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_73, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_74, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_75, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_76, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_77, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_78, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_79, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_80, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_81, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_82, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_83, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_84, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_85, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_86, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_87, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_88, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_89, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_90, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_91, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_92, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_93, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_94, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_95, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_96, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_97, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_98, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_99, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_100, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_101, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_102, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_103, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_104, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_105, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_106, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_107, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_108, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_109, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_110, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_111, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_112, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_113, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_114, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_115, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_116, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_117, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_118, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_119, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_120, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_121, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_122, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_123, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_124, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_125, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_126, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_127, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_128, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_129, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_130, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_131, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_132, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_133, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_134, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_135, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_136, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_137, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_138, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_139, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_140, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_141, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_142, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_143, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_144, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_145, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_146, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_147, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_148, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_149, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_150, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_151, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_152, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_153, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_154, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_155, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_156, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_157, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_158, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_159, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_160, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_161, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_162, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_163, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_164, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_165, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_166, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_167, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_168, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_169, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_170, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_171, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_172, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_173, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_174, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_175, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_176, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_177, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_178, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_179, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_180, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_181, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_182, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_183, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_184, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_185, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_186, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_187, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_188, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_189, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_190, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_191, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_192, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_193, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_194, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_195, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_196, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_197, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_198, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_199, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_200, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_201, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_202, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_203, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_204, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_205, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_206, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_207, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_208, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_209, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_210, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_211, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_212, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_213, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_214, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_215, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_216, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_217, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_218, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_219, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_220, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_221, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_222, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_223, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_224, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_225, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_226, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_227, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_228, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_229, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_230, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_231, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_232, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_233, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_234, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_235, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_236, tvbrange, value) + tvbrange = padded(offset + 243, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_237, tvbrange, value) + tvbrange = padded(offset + 244, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_238, tvbrange, value) + tvbrange = padded(offset + 245, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_239, tvbrange, value) + tvbrange = padded(offset + 246, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_240, tvbrange, value) + tvbrange = padded(offset + 247, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_241, tvbrange, value) + tvbrange = padded(offset + 248, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_242, tvbrange, value) + tvbrange = padded(offset + 249, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_243, tvbrange, value) + tvbrange = padded(offset + 250, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_244, tvbrange, value) + tvbrange = padded(offset + 251, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_245, tvbrange, value) + tvbrange = padded(offset + 252, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_246, tvbrange, value) + tvbrange = padded(offset + 253, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_247, tvbrange, value) + tvbrange = padded(offset + 254, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_data_248, tvbrange, value) end -- dissect payload of message type LOGGING_DATA_ACKED function payload_fns.payload_267(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 255 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 255) @@ -36842,518 +46438,772 @@ function payload_fns.payload_267(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_sequence, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_length, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_first_message_offset, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_0, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_1, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_2, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_3, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_4, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_5, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_6, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_7, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_8, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_9, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_10, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_11, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_12, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_13, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_14, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_15, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_16, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_17, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_18, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_19, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_20, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_21, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_22, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_23, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_24, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_25, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_26, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_27, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_28, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_29, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_30, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_31, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_32, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_33, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_34, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_35, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_36, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_37, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_38, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_39, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_40, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_41, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_42, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_43, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_44, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_45, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_46, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_47, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_48, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_49, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_50, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_51, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_52, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_53, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_54, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_55, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_56, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_57, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_58, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_59, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_60, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_61, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_62, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_63, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_64, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_65, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_66, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_67, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_68, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_69, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_70, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_71, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_72, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_73, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_74, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_75, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_76, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_77, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_78, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_79, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_80, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_81, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_82, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_83, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_84, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_85, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_86, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_87, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_88, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_89, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_90, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_91, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_92, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_93, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_94, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_95, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_96, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_97, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_98, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_99, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_100, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_101, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_102, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_103, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_104, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_105, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_106, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_107, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_108, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_109, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_110, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_111, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_112, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_113, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_114, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_115, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_116, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_117, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_118, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_119, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_120, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_121, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_122, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_123, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_124, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_125, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_126, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_127, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_128, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_129, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_130, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_131, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_132, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_133, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_134, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_135, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_136, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_137, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_138, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_139, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_140, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_141, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_142, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_143, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_144, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_145, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_146, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_147, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_148, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_149, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_150, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_151, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_152, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_153, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_154, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_155, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_156, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_157, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_158, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_159, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_160, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_161, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_162, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_163, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_164, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_165, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_166, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_167, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_168, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_169, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_170, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_171, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_172, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_173, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_174, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_175, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_176, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_177, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_178, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_179, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_180, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_181, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_182, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_183, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_184, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_185, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_186, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_187, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_188, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_189, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_190, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_191, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_192, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_193, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_194, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_195, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_196, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_197, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_198, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_199, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_200, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_201, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_202, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_203, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_204, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_205, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_206, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_207, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_208, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_209, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_210, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_211, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_212, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_213, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_214, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_215, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_216, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_217, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_218, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_219, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_220, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_221, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_222, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_223, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_224, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_225, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_226, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_227, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_228, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_229, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_230, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_231, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_232, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_233, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_234, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_235, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_236, padded(field_offset, 1)) - field_offset = offset + 243 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_237, padded(field_offset, 1)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_238, padded(field_offset, 1)) - field_offset = offset + 245 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_239, padded(field_offset, 1)) - field_offset = offset + 246 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_240, padded(field_offset, 1)) - field_offset = offset + 247 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_241, padded(field_offset, 1)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_242, padded(field_offset, 1)) - field_offset = offset + 249 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_243, padded(field_offset, 1)) - field_offset = offset + 250 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_244, padded(field_offset, 1)) - field_offset = offset + 251 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_245, padded(field_offset, 1)) - field_offset = offset + 252 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_246, padded(field_offset, 1)) - field_offset = offset + 253 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_247, padded(field_offset, 1)) - field_offset = offset + 254 - subtree, value = tree:add_le(f.LOGGING_DATA_ACKED_data_248, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_sequence, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_length, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_first_message_offset, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_0, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_1, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_2, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_3, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_4, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_5, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_6, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_7, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_8, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_9, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_10, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_11, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_12, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_13, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_14, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_15, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_16, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_17, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_18, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_19, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_20, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_21, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_22, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_23, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_24, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_25, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_26, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_27, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_28, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_29, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_30, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_31, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_32, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_33, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_34, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_35, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_36, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_37, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_38, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_39, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_40, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_41, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_42, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_43, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_44, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_45, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_46, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_47, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_48, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_49, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_50, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_51, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_52, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_53, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_54, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_55, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_56, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_57, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_58, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_59, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_60, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_61, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_62, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_63, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_64, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_65, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_66, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_67, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_68, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_69, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_70, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_71, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_72, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_73, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_74, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_75, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_76, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_77, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_78, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_79, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_80, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_81, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_82, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_83, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_84, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_85, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_86, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_87, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_88, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_89, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_90, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_91, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_92, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_93, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_94, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_95, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_96, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_97, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_98, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_99, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_100, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_101, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_102, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_103, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_104, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_105, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_106, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_107, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_108, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_109, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_110, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_111, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_112, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_113, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_114, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_115, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_116, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_117, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_118, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_119, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_120, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_121, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_122, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_123, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_124, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_125, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_126, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_127, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_128, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_129, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_130, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_131, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_132, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_133, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_134, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_135, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_136, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_137, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_138, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_139, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_140, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_141, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_142, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_143, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_144, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_145, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_146, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_147, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_148, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_149, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_150, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_151, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_152, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_153, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_154, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_155, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_156, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_157, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_158, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_159, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_160, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_161, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_162, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_163, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_164, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_165, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_166, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_167, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_168, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_169, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_170, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_171, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_172, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_173, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_174, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_175, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_176, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_177, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_178, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_179, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_180, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_181, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_182, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_183, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_184, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_185, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_186, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_187, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_188, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_189, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_190, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_191, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_192, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_193, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_194, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_195, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_196, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_197, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_198, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_199, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_200, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_201, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_202, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_203, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_204, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_205, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_206, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_207, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_208, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_209, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_210, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_211, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_212, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_213, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_214, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_215, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_216, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_217, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_218, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_219, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_220, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_221, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_222, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_223, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_224, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_225, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_226, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_227, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_228, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_229, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_230, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_231, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_232, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_233, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_234, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_235, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_236, tvbrange, value) + tvbrange = padded(offset + 243, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_237, tvbrange, value) + tvbrange = padded(offset + 244, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_238, tvbrange, value) + tvbrange = padded(offset + 245, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_239, tvbrange, value) + tvbrange = padded(offset + 246, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_240, tvbrange, value) + tvbrange = padded(offset + 247, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_241, tvbrange, value) + tvbrange = padded(offset + 248, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_242, tvbrange, value) + tvbrange = padded(offset + 249, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_243, tvbrange, value) + tvbrange = padded(offset + 250, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_244, tvbrange, value) + tvbrange = padded(offset + 251, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_245, tvbrange, value) + tvbrange = padded(offset + 252, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_246, tvbrange, value) + tvbrange = padded(offset + 253, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_247, tvbrange, value) + tvbrange = padded(offset + 254, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_DATA_ACKED_data_248, tvbrange, value) end -- dissect payload of message type LOGGING_ACK function payload_fns.payload_268(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 4 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 4) @@ -37361,16 +47211,19 @@ function payload_fns.payload_268(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.LOGGING_ACK_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.LOGGING_ACK_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOGGING_ACK_sequence, padded(field_offset, 2)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_ACK_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_ACK_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOGGING_ACK_sequence, tvbrange, value) end -- dissect payload of message type VIDEO_STREAM_INFORMATION function payload_fns.payload_269(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 213 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 213) @@ -37378,35 +47231,47 @@ function payload_fns.payload_269(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 18 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_stream_id, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_count, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_flags, padded(field_offset, 2)) - dissect_flags_VIDEO_STREAM_STATUS_FLAGS(subtree, "VIDEO_STREAM_INFORMATION_flags", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_framerate, padded(field_offset, 4)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_resolution_h, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_resolution_v, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_bitrate, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_rotation, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_hfov, padded(field_offset, 2)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_name, padded(field_offset, 32)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.VIDEO_STREAM_INFORMATION_uri, padded(field_offset, 160)) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_stream_id, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_count, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_type, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_flags, tvbrange, value) + dissect_flags_VIDEO_STREAM_STATUS_FLAGS(subtree, "VIDEO_STREAM_INFORMATION_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_framerate, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_resolution_h, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_resolution_v, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_bitrate, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_rotation, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_hfov, tvbrange, value) + tvbrange = padded(offset + 21, 32) + value = tvbrange:string() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_name, tvbrange, value) + tvbrange = padded(offset + 53, 160) + value = tvbrange:string() + subtree = tree:add_le(f.VIDEO_STREAM_INFORMATION_uri, tvbrange, value) end -- dissect payload of message type VIDEO_STREAM_STATUS function payload_fns.payload_270(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 19 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 19) @@ -37414,27 +47279,35 @@ function payload_fns.payload_270(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 18 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_stream_id, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_flags, padded(field_offset, 2)) - dissect_flags_VIDEO_STREAM_STATUS_FLAGS(subtree, "VIDEO_STREAM_STATUS_flags", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_framerate, padded(field_offset, 4)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_resolution_h, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_resolution_v, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_bitrate, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_rotation, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.VIDEO_STREAM_STATUS_hfov, padded(field_offset, 2)) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_stream_id, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_flags, tvbrange, value) + dissect_flags_VIDEO_STREAM_STATUS_FLAGS(subtree, "VIDEO_STREAM_STATUS_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_framerate, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_resolution_h, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_resolution_v, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_bitrate, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_rotation, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.VIDEO_STREAM_STATUS_hfov, tvbrange, value) end -- dissect payload of message type CAMERA_FOV_STATUS function payload_fns.payload_271(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 52 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 52) @@ -37442,36 +47315,49 @@ function payload_fns.payload_271(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_lat_camera, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_lon_camera, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_alt_camera, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_lat_image, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_lon_image, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_alt_image, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_q_0, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_q_1, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_q_2, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_q_3, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_hfov, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.CAMERA_FOV_STATUS_vfov, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_lat_camera, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_lon_camera, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_alt_camera, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_lat_image, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_lon_image, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_alt_image, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_q_0, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_q_1, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_q_2, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_q_3, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_hfov, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_FOV_STATUS_vfov, tvbrange, value) end -- dissect payload of message type CAMERA_TRACKING_IMAGE_STATUS function payload_fns.payload_275(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 31 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 31) @@ -37479,30 +47365,41 @@ function payload_fns.payload_275(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_tracking_status, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_tracking_mode, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_target_data, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_point_x, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_point_y, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_radius, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_top_x, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_top_y, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_bottom_x, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_bottom_y, padded(field_offset, 4)) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_tracking_status, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_tracking_mode, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_target_data, tvbrange, value) + dissect_flags_CAMERA_TRACKING_TARGET_DATA(subtree, "CAMERA_TRACKING_IMAGE_STATUS_target_data", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_point_x, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_point_y, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_radius, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_top_x, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_top_y, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_bottom_x, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_IMAGE_STATUS_rec_bottom_y, tvbrange, value) end -- dissect payload of message type CAMERA_TRACKING_GEO_STATUS function payload_fns.payload_276(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 49 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 49) @@ -37510,36 +47407,121 @@ function payload_fns.payload_276(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 48 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_tracking_status, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_lat, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_lon, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_alt, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_h_acc, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_v_acc, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_n, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_e, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_d, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_acc, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_dist, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_hdg, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_hdg_acc, padded(field_offset, 4)) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_tracking_status, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_lat, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_lon, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_alt, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_h_acc, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_v_acc, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_n, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_e, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_d, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_vel_acc, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_dist, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_hdg, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.CAMERA_TRACKING_GEO_STATUS_hdg_acc, tvbrange, value) +end +-- dissect payload of message type GIMBAL_MANAGER_INFORMATION +function payload_fns.payload_280(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 33 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 33) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_cap_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_CAP_FLAGS(subtree, "GIMBAL_MANAGER_INFORMATION_cap_flags", tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_gimbal_device_id, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_roll_min, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_roll_max, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_pitch_min, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_pitch_max, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_yaw_min, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_INFORMATION_yaw_max, tvbrange, value) +end +-- dissect payload of message type GIMBAL_MANAGER_STATUS +function payload_fns.payload_281(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 13 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 13) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_STATUS_flags", tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_gimbal_device_id, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_primary_control_sysid, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_primary_control_compid, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_secondary_control_sysid, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_secondary_control_compid, tvbrange, value) end -- dissect payload of message type GIMBAL_DEVICE_INFORMATION function payload_fns.payload_283(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 144 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 144) @@ -37547,41 +47529,56 @@ function payload_fns.payload_283(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_vendor_name, padded(field_offset, 32)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_model_name, padded(field_offset, 32)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_custom_name, padded(field_offset, 32)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_firmware_version, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_hardware_version, padded(field_offset, 4)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_uid, padded(field_offset, 8)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_cap_flags, padded(field_offset, 2)) - dissect_flags_GIMBAL_DEVICE_CAP_FLAGS(subtree, "GIMBAL_DEVICE_INFORMATION_cap_flags", value) - field_offset = offset + 46 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_custom_cap_flags, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_roll_min, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_roll_max, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_pitch_min, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_pitch_max, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_yaw_min, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_yaw_max, padded(field_offset, 4)) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 48, 32) + value = tvbrange:string() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_vendor_name, tvbrange, value) + tvbrange = padded(offset + 80, 32) + value = tvbrange:string() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_model_name, tvbrange, value) + tvbrange = padded(offset + 112, 32) + value = tvbrange:string() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_custom_name, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_firmware_version, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_hardware_version, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_uid, tvbrange, value) + tvbrange = padded(offset + 44, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_cap_flags, tvbrange, value) + dissect_flags_GIMBAL_DEVICE_CAP_FLAGS(subtree, "GIMBAL_DEVICE_INFORMATION_cap_flags", tvbrange, value) + tvbrange = padded(offset + 46, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_custom_cap_flags, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_roll_min, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_roll_max, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_pitch_min, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_pitch_max, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_yaw_min, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_yaw_max, tvbrange, value) end -- dissect payload of message type GIMBAL_DEVICE_SET_ATTITUDE function payload_fns.payload_284(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 32 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 32) @@ -37589,31 +47586,41 @@ function payload_fns.payload_284(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_target_component, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_flags, padded(field_offset, 2)) - dissect_flags_GIMBAL_DEVICE_FLAGS(subtree, "GIMBAL_DEVICE_SET_ATTITUDE_flags", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_0, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_1, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_2, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_3, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_angular_velocity_x, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_angular_velocity_y, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_angular_velocity_z, padded(field_offset, 4)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_target_component, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_flags, tvbrange, value) + dissect_flags_GIMBAL_DEVICE_FLAGS(subtree, "GIMBAL_DEVICE_SET_ATTITUDE_flags", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_0, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_1, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_q_3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_SET_ATTITUDE_angular_velocity_z, tvbrange, value) end -- dissect payload of message type GIMBAL_DEVICE_ATTITUDE_STATUS function payload_fns.payload_285(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 40 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 40) @@ -37621,36 +47628,48 @@ function payload_fns.payload_285(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 38 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_system, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_time_boot_ms, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags, padded(field_offset, 2)) - dissect_flags_GIMBAL_DEVICE_FLAGS(subtree, "GIMBAL_DEVICE_ATTITUDE_STATUS_flags", value) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_0, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_1, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_2, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_3, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_x, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_y, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_z, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags, padded(field_offset, 4)) - dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(subtree, "GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags", value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_system, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags, tvbrange, value) + dissect_flags_GIMBAL_DEVICE_FLAGS(subtree, "GIMBAL_DEVICE_ATTITUDE_STATUS_flags", tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_angular_velocity_z, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags, tvbrange, value) + dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(subtree, "GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags", tvbrange, value) end -- dissect payload of message type AUTOPILOT_STATE_FOR_GIMBAL_DEVICE function payload_fns.payload_286(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 53 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 53) @@ -37658,41 +47677,56 @@ function payload_fns.payload_286(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 50 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_system, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_time_boot_us, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_0, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_1, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_2, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_3, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_estimated_delay_us, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vx, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vy, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vz, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_v_estimated_delay_us, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_feed_forward_angular_velocity_z, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status, padded(field_offset, 2)) - dissect_flags_ESTIMATOR_STATUS_FLAGS(subtree, "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status", value) - field_offset = offset + 52 - subtree, value = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state, padded(field_offset, 1)) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_system, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_time_boot_us, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_0, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_1, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_2, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_3, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_q_estimated_delay_us, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vx, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vy, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_vz, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_v_estimated_delay_us, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_feed_forward_angular_velocity_z, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status, tvbrange, value) + dissect_flags_ESTIMATOR_STATUS_FLAGS(subtree, "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status", tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state, tvbrange, value) end -- dissect payload of message type GIMBAL_MANAGER_SET_ATTITUDE function payload_fns.payload_282(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 35 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 35) @@ -37700,33 +47734,80 @@ function payload_fns.payload_282(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 32 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_system, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_flags, padded(field_offset, 4)) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_ATTITUDE_flags", value) - field_offset = offset + 34 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_0, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_1, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_2, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_3, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z, padded(field_offset, 4)) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_system, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_ATTITUDE_flags", tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_gimbal_device_id, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_0, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_1, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_2, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_q_3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_y, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_z, tvbrange, value) +end +-- dissect payload of message type GIMBAL_MANAGER_SET_PITCHYAW +function payload_fns.payload_287(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 23 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 23) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_system, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_PITCHYAW_flags", tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_gimbal_device_id, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_pitch, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_pitch_rate, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate, tvbrange, value) end -- dissect payload of message type WIFI_CONFIG_AP function payload_fns.payload_299(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 96 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 96) @@ -37734,14 +47815,16 @@ function payload_fns.payload_299(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.WIFI_CONFIG_AP_ssid, padded(field_offset, 32)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.WIFI_CONFIG_AP_password, padded(field_offset, 64)) + tvbrange = padded(offset + 0, 32) + value = tvbrange:string() + subtree = tree:add_le(f.WIFI_CONFIG_AP_ssid, tvbrange, value) + tvbrange = padded(offset + 32, 64) + value = tvbrange:string() + subtree = tree:add_le(f.WIFI_CONFIG_AP_password, tvbrange, value) end -- dissect payload of message type AIS_VESSEL function payload_fns.payload_301(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 58 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 58) @@ -37749,45 +47832,62 @@ function payload_fns.payload_301(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.AIS_VESSEL_MMSI, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.AIS_VESSEL_lat, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.AIS_VESSEL_lon, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.AIS_VESSEL_COG, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.AIS_VESSEL_heading, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.AIS_VESSEL_velocity, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.AIS_VESSEL_turn_rate, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.AIS_VESSEL_navigational_status, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.AIS_VESSEL_type, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.AIS_VESSEL_dimension_bow, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.AIS_VESSEL_dimension_stern, padded(field_offset, 2)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.AIS_VESSEL_dimension_port, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.AIS_VESSEL_dimension_starboard, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.AIS_VESSEL_callsign, padded(field_offset, 7)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.AIS_VESSEL_name, padded(field_offset, 20)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.AIS_VESSEL_tslc, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.AIS_VESSEL_flags, padded(field_offset, 2)) - dissect_flags_AIS_FLAGS(subtree, "AIS_VESSEL_flags", value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_MMSI, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AIS_VESSEL_lat, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.AIS_VESSEL_lon, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_COG, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_heading, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_velocity, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.AIS_VESSEL_turn_rate, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_navigational_status, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_type, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_dimension_bow, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_dimension_stern, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_dimension_port, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_dimension_starboard, tvbrange, value) + tvbrange = padded(offset + 31, 7) + value = tvbrange:string() + subtree = tree:add_le(f.AIS_VESSEL_callsign, tvbrange, value) + tvbrange = padded(offset + 38, 20) + value = tvbrange:string() + subtree = tree:add_le(f.AIS_VESSEL_name, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_tslc, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIS_VESSEL_flags, tvbrange, value) + dissect_flags_AIS_FLAGS(subtree, "AIS_VESSEL_flags", tvbrange, value) end -- dissect payload of message type UAVCAN_NODE_STATUS function payload_fns.payload_310(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 17 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 17) @@ -37795,22 +47895,28 @@ function payload_fns.payload_310(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVCAN_NODE_STATUS_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.UAVCAN_NODE_STATUS_uptime_sec, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.UAVCAN_NODE_STATUS_health, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.UAVCAN_NODE_STATUS_mode, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.UAVCAN_NODE_STATUS_sub_mode, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.UAVCAN_NODE_STATUS_vendor_specific_status_code, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.UAVCAN_NODE_STATUS_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_STATUS_uptime_sec, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_STATUS_health, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_STATUS_mode, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_STATUS_sub_mode, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_STATUS_vendor_specific_status_code, tvbrange, value) end -- dissect payload of message type UAVCAN_NODE_INFO function payload_fns.payload_311(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 116 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 116) @@ -37818,58 +47924,82 @@ function payload_fns.payload_311(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_uptime_sec, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_name, padded(field_offset, 80)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_version_major, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_version_minor, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_0, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_1, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_2, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_3, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_4, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_5, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_6, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_7, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_8, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_9, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_10, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_11, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_12, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_13, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_14, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_15, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_sw_version_major, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_sw_version_minor, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.UAVCAN_NODE_INFO_sw_vcs_commit, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_uptime_sec, tvbrange, value) + tvbrange = padded(offset + 16, 80) + value = tvbrange:string() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_name, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_version_major, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_version_minor, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_0, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_1, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_2, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_3, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_4, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_5, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_6, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_7, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_8, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_9, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_10, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_11, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_12, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_13, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_14, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_hw_unique_id_15, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_sw_version_major, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_sw_version_minor, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVCAN_NODE_INFO_sw_vcs_commit, tvbrange, value) end -- dissect payload of message type PARAM_EXT_REQUEST_READ function payload_fns.payload_320(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -37877,18 +48007,22 @@ function payload_fns.payload_320(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.PARAM_EXT_REQUEST_READ_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.PARAM_EXT_REQUEST_READ_target_component, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.PARAM_EXT_REQUEST_READ_param_id, padded(field_offset, 16)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_EXT_REQUEST_READ_param_index, padded(field_offset, 2)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_REQUEST_READ_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_REQUEST_READ_target_component, tvbrange, value) + tvbrange = padded(offset + 4, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_REQUEST_READ_param_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.PARAM_EXT_REQUEST_READ_param_index, tvbrange, value) end -- dissect payload of message type PARAM_EXT_REQUEST_LIST function payload_fns.payload_321(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 2 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 2) @@ -37896,14 +48030,16 @@ function payload_fns.payload_321(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_EXT_REQUEST_LIST_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.PARAM_EXT_REQUEST_LIST_target_component, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_REQUEST_LIST_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_REQUEST_LIST_target_component, tvbrange, value) end -- dissect payload of message type PARAM_EXT_VALUE function payload_fns.payload_322(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 149 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 149) @@ -37911,20 +48047,25 @@ function payload_fns.payload_322(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.PARAM_EXT_VALUE_param_id, padded(field_offset, 16)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.PARAM_EXT_VALUE_param_value, padded(field_offset, 128)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.PARAM_EXT_VALUE_param_type, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_EXT_VALUE_param_count, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.PARAM_EXT_VALUE_param_index, padded(field_offset, 2)) + tvbrange = padded(offset + 4, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_VALUE_param_id, tvbrange, value) + tvbrange = padded(offset + 20, 128) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_VALUE_param_value, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_VALUE_param_type, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_VALUE_param_count, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_VALUE_param_index, tvbrange, value) end -- dissect payload of message type PARAM_EXT_SET function payload_fns.payload_323(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 147 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 147) @@ -37932,20 +48073,25 @@ function payload_fns.payload_323(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_EXT_SET_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.PARAM_EXT_SET_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.PARAM_EXT_SET_param_id, padded(field_offset, 16)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.PARAM_EXT_SET_param_value, padded(field_offset, 128)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.PARAM_EXT_SET_param_type, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_SET_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_SET_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_SET_param_id, tvbrange, value) + tvbrange = padded(offset + 18, 128) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_SET_param_value, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_SET_param_type, tvbrange, value) end -- dissect payload of message type PARAM_EXT_ACK function payload_fns.payload_324(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 146 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 146) @@ -37953,18 +48099,22 @@ function payload_fns.payload_324(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.PARAM_EXT_ACK_param_id, padded(field_offset, 16)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.PARAM_EXT_ACK_param_value, padded(field_offset, 128)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.PARAM_EXT_ACK_param_type, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.PARAM_EXT_ACK_param_result, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 16) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_ACK_param_id, tvbrange, value) + tvbrange = padded(offset + 16, 128) + value = tvbrange:string() + subtree = tree:add_le(f.PARAM_EXT_ACK_param_value, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_ACK_param_type, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.PARAM_EXT_ACK_param_result, tvbrange, value) end -- dissect payload of message type OBSTACLE_DISTANCE function payload_fns.payload_330(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 167 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 167) @@ -37972,301 +48122,444 @@ function payload_fns.payload_330(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_time_usec, padded(field_offset, 8)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_sensor_type, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_0, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_1, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_2, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_3, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_4, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_5, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_6, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_7, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_8, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_9, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_10, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_11, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_12, padded(field_offset, 2)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_13, padded(field_offset, 2)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_14, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_15, padded(field_offset, 2)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_16, padded(field_offset, 2)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_17, padded(field_offset, 2)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_18, padded(field_offset, 2)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_19, padded(field_offset, 2)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_20, padded(field_offset, 2)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_21, padded(field_offset, 2)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_22, padded(field_offset, 2)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_23, padded(field_offset, 2)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_24, padded(field_offset, 2)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_25, padded(field_offset, 2)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_26, padded(field_offset, 2)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_27, padded(field_offset, 2)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_28, padded(field_offset, 2)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_29, padded(field_offset, 2)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_30, padded(field_offset, 2)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_31, padded(field_offset, 2)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_32, padded(field_offset, 2)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_33, padded(field_offset, 2)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_34, padded(field_offset, 2)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_35, padded(field_offset, 2)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_36, padded(field_offset, 2)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_37, padded(field_offset, 2)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_38, padded(field_offset, 2)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_39, padded(field_offset, 2)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_40, padded(field_offset, 2)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_41, padded(field_offset, 2)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_42, padded(field_offset, 2)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_43, padded(field_offset, 2)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_44, padded(field_offset, 2)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_45, padded(field_offset, 2)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_46, padded(field_offset, 2)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_47, padded(field_offset, 2)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_48, padded(field_offset, 2)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_49, padded(field_offset, 2)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_50, padded(field_offset, 2)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_51, padded(field_offset, 2)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_52, padded(field_offset, 2)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_53, padded(field_offset, 2)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_54, padded(field_offset, 2)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_55, padded(field_offset, 2)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_56, padded(field_offset, 2)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_57, padded(field_offset, 2)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_58, padded(field_offset, 2)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_59, padded(field_offset, 2)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_60, padded(field_offset, 2)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_61, padded(field_offset, 2)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_62, padded(field_offset, 2)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_63, padded(field_offset, 2)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_64, padded(field_offset, 2)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_65, padded(field_offset, 2)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_66, padded(field_offset, 2)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_67, padded(field_offset, 2)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_68, padded(field_offset, 2)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_69, padded(field_offset, 2)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_70, padded(field_offset, 2)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_distances_71, padded(field_offset, 2)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_increment, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_min_distance, padded(field_offset, 2)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_max_distance, padded(field_offset, 2)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_increment_f, padded(field_offset, 4)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_angle_offset, padded(field_offset, 4)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.OBSTACLE_DISTANCE_frame, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_time_usec, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_sensor_type, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_0, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_1, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_2, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_3, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_4, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_5, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_6, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_7, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_8, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_9, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_10, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_11, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_12, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_13, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_14, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_15, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_16, tvbrange, value) + tvbrange = padded(offset + 42, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_17, tvbrange, value) + tvbrange = padded(offset + 44, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_18, tvbrange, value) + tvbrange = padded(offset + 46, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_19, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_20, tvbrange, value) + tvbrange = padded(offset + 50, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_21, tvbrange, value) + tvbrange = padded(offset + 52, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_22, tvbrange, value) + tvbrange = padded(offset + 54, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_23, tvbrange, value) + tvbrange = padded(offset + 56, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_24, tvbrange, value) + tvbrange = padded(offset + 58, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_25, tvbrange, value) + tvbrange = padded(offset + 60, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_26, tvbrange, value) + tvbrange = padded(offset + 62, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_27, tvbrange, value) + tvbrange = padded(offset + 64, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_28, tvbrange, value) + tvbrange = padded(offset + 66, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_29, tvbrange, value) + tvbrange = padded(offset + 68, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_30, tvbrange, value) + tvbrange = padded(offset + 70, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_31, tvbrange, value) + tvbrange = padded(offset + 72, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_32, tvbrange, value) + tvbrange = padded(offset + 74, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_33, tvbrange, value) + tvbrange = padded(offset + 76, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_34, tvbrange, value) + tvbrange = padded(offset + 78, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_35, tvbrange, value) + tvbrange = padded(offset + 80, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_36, tvbrange, value) + tvbrange = padded(offset + 82, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_37, tvbrange, value) + tvbrange = padded(offset + 84, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_38, tvbrange, value) + tvbrange = padded(offset + 86, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_39, tvbrange, value) + tvbrange = padded(offset + 88, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_40, tvbrange, value) + tvbrange = padded(offset + 90, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_41, tvbrange, value) + tvbrange = padded(offset + 92, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_42, tvbrange, value) + tvbrange = padded(offset + 94, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_43, tvbrange, value) + tvbrange = padded(offset + 96, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_44, tvbrange, value) + tvbrange = padded(offset + 98, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_45, tvbrange, value) + tvbrange = padded(offset + 100, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_46, tvbrange, value) + tvbrange = padded(offset + 102, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_47, tvbrange, value) + tvbrange = padded(offset + 104, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_48, tvbrange, value) + tvbrange = padded(offset + 106, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_49, tvbrange, value) + tvbrange = padded(offset + 108, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_50, tvbrange, value) + tvbrange = padded(offset + 110, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_51, tvbrange, value) + tvbrange = padded(offset + 112, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_52, tvbrange, value) + tvbrange = padded(offset + 114, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_53, tvbrange, value) + tvbrange = padded(offset + 116, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_54, tvbrange, value) + tvbrange = padded(offset + 118, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_55, tvbrange, value) + tvbrange = padded(offset + 120, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_56, tvbrange, value) + tvbrange = padded(offset + 122, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_57, tvbrange, value) + tvbrange = padded(offset + 124, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_58, tvbrange, value) + tvbrange = padded(offset + 126, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_59, tvbrange, value) + tvbrange = padded(offset + 128, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_60, tvbrange, value) + tvbrange = padded(offset + 130, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_61, tvbrange, value) + tvbrange = padded(offset + 132, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_62, tvbrange, value) + tvbrange = padded(offset + 134, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_63, tvbrange, value) + tvbrange = padded(offset + 136, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_64, tvbrange, value) + tvbrange = padded(offset + 138, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_65, tvbrange, value) + tvbrange = padded(offset + 140, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_66, tvbrange, value) + tvbrange = padded(offset + 142, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_67, tvbrange, value) + tvbrange = padded(offset + 144, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_68, tvbrange, value) + tvbrange = padded(offset + 146, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_69, tvbrange, value) + tvbrange = padded(offset + 148, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_70, tvbrange, value) + tvbrange = padded(offset + 150, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_distances_71, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_increment, tvbrange, value) + tvbrange = padded(offset + 152, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_min_distance, tvbrange, value) + tvbrange = padded(offset + 154, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_max_distance, tvbrange, value) + tvbrange = padded(offset + 158, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_increment_f, tvbrange, value) + tvbrange = padded(offset + 162, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_angle_offset, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OBSTACLE_DISTANCE_frame, tvbrange, value) end -- dissect payload of message type ODOMETRY function payload_fns.payload_331(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree - if (offset + 232 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 232) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ODOMETRY_time_usec, padded(field_offset, 8)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.ODOMETRY_frame_id, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.ODOMETRY_child_frame_id, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ODOMETRY_x, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ODOMETRY_y, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ODOMETRY_z, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ODOMETRY_q_0, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ODOMETRY_q_1, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ODOMETRY_q_2, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ODOMETRY_q_3, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ODOMETRY_vx, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ODOMETRY_vy, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ODOMETRY_vz, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.ODOMETRY_rollspeed, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.ODOMETRY_pitchspeed, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.ODOMETRY_yawspeed, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_0, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_1, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_2, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_3, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_4, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_5, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_6, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_7, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_8, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_9, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_10, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_11, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_12, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_13, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_14, padded(field_offset, 4)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_15, padded(field_offset, 4)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_16, padded(field_offset, 4)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_17, padded(field_offset, 4)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_18, padded(field_offset, 4)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_19, padded(field_offset, 4)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.ODOMETRY_pose_covariance_20, padded(field_offset, 4)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_0, padded(field_offset, 4)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_1, padded(field_offset, 4)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_2, padded(field_offset, 4)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_3, padded(field_offset, 4)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_4, padded(field_offset, 4)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_5, padded(field_offset, 4)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_6, padded(field_offset, 4)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_7, padded(field_offset, 4)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_8, padded(field_offset, 4)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_9, padded(field_offset, 4)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_10, padded(field_offset, 4)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_11, padded(field_offset, 4)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_12, padded(field_offset, 4)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_13, padded(field_offset, 4)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_14, padded(field_offset, 4)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_15, padded(field_offset, 4)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_16, padded(field_offset, 4)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_17, padded(field_offset, 4)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_18, padded(field_offset, 4)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_19, padded(field_offset, 4)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.ODOMETRY_velocity_covariance_20, padded(field_offset, 4)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.ODOMETRY_reset_counter, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.ODOMETRY_estimator_type, padded(field_offset, 1)) + local padded, field_offset, value, subtree, tvbrange + if (offset + 233 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 233) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ODOMETRY_time_usec, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ODOMETRY_frame_id, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ODOMETRY_child_frame_id, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_x, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_y, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_z, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_q_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_q_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_q_2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_q_3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_vx, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_vy, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_vz, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_rollspeed, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pitchspeed, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_yawspeed, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_0, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_1, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_2, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_3, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_4, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_5, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_6, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_7, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_8, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_9, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_10, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_11, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_12, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_13, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_14, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_15, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_16, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_17, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_18, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_19, tvbrange, value) + tvbrange = padded(offset + 140, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_pose_covariance_20, tvbrange, value) + tvbrange = padded(offset + 144, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_0, tvbrange, value) + tvbrange = padded(offset + 148, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_1, tvbrange, value) + tvbrange = padded(offset + 152, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_2, tvbrange, value) + tvbrange = padded(offset + 156, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_3, tvbrange, value) + tvbrange = padded(offset + 160, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_4, tvbrange, value) + tvbrange = padded(offset + 164, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_5, tvbrange, value) + tvbrange = padded(offset + 168, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_6, tvbrange, value) + tvbrange = padded(offset + 172, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_7, tvbrange, value) + tvbrange = padded(offset + 176, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_8, tvbrange, value) + tvbrange = padded(offset + 180, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_9, tvbrange, value) + tvbrange = padded(offset + 184, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_10, tvbrange, value) + tvbrange = padded(offset + 188, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_11, tvbrange, value) + tvbrange = padded(offset + 192, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_12, tvbrange, value) + tvbrange = padded(offset + 196, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_13, tvbrange, value) + tvbrange = padded(offset + 200, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_14, tvbrange, value) + tvbrange = padded(offset + 204, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_15, tvbrange, value) + tvbrange = padded(offset + 208, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_16, tvbrange, value) + tvbrange = padded(offset + 212, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_17, tvbrange, value) + tvbrange = padded(offset + 216, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_18, tvbrange, value) + tvbrange = padded(offset + 220, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_19, tvbrange, value) + tvbrange = padded(offset + 224, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ODOMETRY_velocity_covariance_20, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ODOMETRY_reset_counter, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ODOMETRY_estimator_type, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ODOMETRY_quality, tvbrange, value) end -- dissect payload of message type ISBD_LINK_STATUS function payload_fns.payload_335(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 24 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 24) @@ -38274,26 +48567,34 @@ function payload_fns.payload_335(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_timestamp, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_last_heartbeat, padded(field_offset, 8)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_failed_sessions, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_successful_sessions, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_signal_quality, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_ring_pending, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_tx_session_pending, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.ISBD_LINK_STATUS_rx_session_pending, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ISBD_LINK_STATUS_timestamp, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ISBD_LINK_STATUS_last_heartbeat, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ISBD_LINK_STATUS_failed_sessions, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ISBD_LINK_STATUS_successful_sessions, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ISBD_LINK_STATUS_signal_quality, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ISBD_LINK_STATUS_ring_pending, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ISBD_LINK_STATUS_tx_session_pending, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ISBD_LINK_STATUS_rx_session_pending, tvbrange, value) end -- dissect payload of message type RAW_RPM function payload_fns.payload_339(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -38301,14 +48602,16 @@ function payload_fns.payload_339(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.RAW_RPM_index, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.RAW_RPM_frequency, padded(field_offset, 4)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RAW_RPM_index, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.RAW_RPM_frequency, tvbrange, value) end -- dissect payload of message type UTM_GLOBAL_POSITION function payload_fns.payload_340(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 70 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 70) @@ -38316,81 +48619,116 @@ function payload_fns.payload_340(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_time, padded(field_offset, 8)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_0, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_1, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_2, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_3, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_4, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_5, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_6, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_7, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_8, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_9, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_10, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_11, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_12, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_13, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_14, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_15, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_16, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_17, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_lat, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_lon, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_alt, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_relative_alt, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_vx, padded(field_offset, 2)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_vy, padded(field_offset, 2)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_vz, padded(field_offset, 2)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_h_acc, padded(field_offset, 2)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_v_acc, padded(field_offset, 2)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_vel_acc, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_next_lat, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_next_lon, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_next_alt, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_update_rate, padded(field_offset, 2)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_flight_state, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.UTM_GLOBAL_POSITION_flags, padded(field_offset, 1)) - dissect_flags_UTM_DATA_AVAIL_FLAGS(subtree, "UTM_GLOBAL_POSITION_flags", value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_time, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_0, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_1, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_2, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_3, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_4, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_5, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_6, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_7, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_8, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_9, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_10, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_11, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_12, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_13, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_14, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_15, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_16, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_uas_id_17, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_lat, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_lon, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_alt, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_relative_alt, tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_vx, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_vy, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_vz, tvbrange, value) + tvbrange = padded(offset + 42, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_h_acc, tvbrange, value) + tvbrange = padded(offset + 44, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_v_acc, tvbrange, value) + tvbrange = padded(offset + 46, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_vel_acc, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_next_lat, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_next_lon, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_next_alt, tvbrange, value) + tvbrange = padded(offset + 48, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_update_rate, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_flight_state, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UTM_GLOBAL_POSITION_flags, tvbrange, value) + dissect_flags_UTM_DATA_AVAIL_FLAGS(subtree, "UTM_GLOBAL_POSITION_flags", tvbrange, value) end -- dissect payload of message type DEBUG_FLOAT_ARRAY function payload_fns.payload_350(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 252 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 252) @@ -38398,132 +48736,193 @@ function payload_fns.payload_350(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_time_usec, padded(field_offset, 8)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_name, padded(field_offset, 10)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_array_id, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_0, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_1, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_2, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_3, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_4, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_5, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_6, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_7, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_8, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_9, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_10, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_11, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_12, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_13, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_14, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_15, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_16, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_17, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_18, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_19, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_20, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_21, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_22, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_23, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_24, padded(field_offset, 4)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_25, padded(field_offset, 4)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_26, padded(field_offset, 4)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_27, padded(field_offset, 4)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_28, padded(field_offset, 4)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_29, padded(field_offset, 4)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_30, padded(field_offset, 4)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_31, padded(field_offset, 4)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_32, padded(field_offset, 4)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_33, padded(field_offset, 4)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_34, padded(field_offset, 4)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_35, padded(field_offset, 4)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_36, padded(field_offset, 4)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_37, padded(field_offset, 4)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_38, padded(field_offset, 4)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_39, padded(field_offset, 4)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_40, padded(field_offset, 4)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_41, padded(field_offset, 4)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_42, padded(field_offset, 4)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_43, padded(field_offset, 4)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_44, padded(field_offset, 4)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_45, padded(field_offset, 4)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_46, padded(field_offset, 4)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_47, padded(field_offset, 4)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_48, padded(field_offset, 4)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_49, padded(field_offset, 4)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_50, padded(field_offset, 4)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_51, padded(field_offset, 4)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_52, padded(field_offset, 4)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_53, padded(field_offset, 4)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_54, padded(field_offset, 4)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_55, padded(field_offset, 4)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_56, padded(field_offset, 4)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_57, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_time_usec, tvbrange, value) + tvbrange = padded(offset + 10, 10) + value = tvbrange:string() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_name, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_array_id, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_0, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_1, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_2, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_3, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_4, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_5, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_6, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_7, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_8, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_9, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_10, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_11, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_12, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_13, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_14, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_15, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_16, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_17, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_18, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_19, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_20, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_21, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_22, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_23, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_24, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_25, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_26, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_27, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_28, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_29, tvbrange, value) + tvbrange = padded(offset + 140, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_30, tvbrange, value) + tvbrange = padded(offset + 144, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_31, tvbrange, value) + tvbrange = padded(offset + 148, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_32, tvbrange, value) + tvbrange = padded(offset + 152, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_33, tvbrange, value) + tvbrange = padded(offset + 156, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_34, tvbrange, value) + tvbrange = padded(offset + 160, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_35, tvbrange, value) + tvbrange = padded(offset + 164, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_36, tvbrange, value) + tvbrange = padded(offset + 168, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_37, tvbrange, value) + tvbrange = padded(offset + 172, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_38, tvbrange, value) + tvbrange = padded(offset + 176, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_39, tvbrange, value) + tvbrange = padded(offset + 180, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_40, tvbrange, value) + tvbrange = padded(offset + 184, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_41, tvbrange, value) + tvbrange = padded(offset + 188, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_42, tvbrange, value) + tvbrange = padded(offset + 192, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_43, tvbrange, value) + tvbrange = padded(offset + 196, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_44, tvbrange, value) + tvbrange = padded(offset + 200, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_45, tvbrange, value) + tvbrange = padded(offset + 204, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_46, tvbrange, value) + tvbrange = padded(offset + 208, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_47, tvbrange, value) + tvbrange = padded(offset + 212, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_48, tvbrange, value) + tvbrange = padded(offset + 216, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_49, tvbrange, value) + tvbrange = padded(offset + 220, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_50, tvbrange, value) + tvbrange = padded(offset + 224, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_51, tvbrange, value) + tvbrange = padded(offset + 228, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_52, tvbrange, value) + tvbrange = padded(offset + 232, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_53, tvbrange, value) + tvbrange = padded(offset + 236, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_54, tvbrange, value) + tvbrange = padded(offset + 240, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_55, tvbrange, value) + tvbrange = padded(offset + 244, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_56, tvbrange, value) + tvbrange = padded(offset + 248, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.DEBUG_FLOAT_ARRAY_data_57, tvbrange, value) end -- dissect payload of message type SMART_BATTERY_INFO function payload_fns.payload_370(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 109 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 109) @@ -38531,44 +48930,61 @@ function payload_fns.payload_370(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 18 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_id, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_battery_function, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_type, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_capacity_full_specification, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_capacity_full, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_cycle_count, padded(field_offset, 2)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_serial_number, padded(field_offset, 16)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_device_name, padded(field_offset, 50)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_weight, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_discharge_minimum_voltage, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_charging_minimum_voltage, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_resting_minimum_voltage, padded(field_offset, 2)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_charging_maximum_voltage, padded(field_offset, 2)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_cells_in_series, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_discharge_maximum_current, padded(field_offset, 4)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_discharge_maximum_burst_current, padded(field_offset, 4)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.SMART_BATTERY_INFO_manufacture_date, padded(field_offset, 11)) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_id, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_battery_function, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_type, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SMART_BATTERY_INFO_capacity_full_specification, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.SMART_BATTERY_INFO_capacity_full, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_cycle_count, tvbrange, value) + tvbrange = padded(offset + 21, 16) + value = tvbrange:string() + subtree = tree:add_le(f.SMART_BATTERY_INFO_serial_number, tvbrange, value) + tvbrange = padded(offset + 37, 50) + value = tvbrange:string() + subtree = tree:add_le(f.SMART_BATTERY_INFO_device_name, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_weight, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_discharge_minimum_voltage, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_charging_minimum_voltage, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_resting_minimum_voltage, tvbrange, value) + tvbrange = padded(offset + 87, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_charging_maximum_voltage, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_cells_in_series, tvbrange, value) + tvbrange = padded(offset + 90, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_discharge_maximum_current, tvbrange, value) + tvbrange = padded(offset + 94, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.SMART_BATTERY_INFO_discharge_maximum_burst_current, tvbrange, value) + tvbrange = padded(offset + 98, 11) + value = tvbrange:string() + subtree = tree:add_le(f.SMART_BATTERY_INFO_manufacture_date, tvbrange, value) end -- dissect payload of message type GENERATOR_STATUS function payload_fns.payload_373(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 42 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 42) @@ -38576,33 +48992,44 @@ function payload_fns.payload_373(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.GENERATOR_STATUS_status, padded(field_offset, 8)) - dissect_flags_MAV_GENERATOR_STATUS_FLAG(subtree, "GENERATOR_STATUS_status", value) - field_offset = offset + 36 - subtree, value = tree:add_le(f.GENERATOR_STATUS_generator_speed, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.GENERATOR_STATUS_battery_current, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.GENERATOR_STATUS_load_current, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.GENERATOR_STATUS_power_generated, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.GENERATOR_STATUS_bus_voltage, padded(field_offset, 4)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.GENERATOR_STATUS_rectifier_temperature, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.GENERATOR_STATUS_bat_current_setpoint, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.GENERATOR_STATUS_generator_temperature, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.GENERATOR_STATUS_runtime, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.GENERATOR_STATUS_time_until_maintenance, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.GENERATOR_STATUS_status, tvbrange, value) + dissect_flags_MAV_GENERATOR_STATUS_FLAG(subtree, "GENERATOR_STATUS_status", tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GENERATOR_STATUS_generator_speed, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GENERATOR_STATUS_battery_current, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GENERATOR_STATUS_load_current, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GENERATOR_STATUS_power_generated, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GENERATOR_STATUS_bus_voltage, tvbrange, value) + tvbrange = padded(offset + 38, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GENERATOR_STATUS_rectifier_temperature, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GENERATOR_STATUS_bat_current_setpoint, tvbrange, value) + tvbrange = padded(offset + 40, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.GENERATOR_STATUS_generator_temperature, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GENERATOR_STATUS_runtime, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.GENERATOR_STATUS_time_until_maintenance, tvbrange, value) end -- dissect payload of message type ACTUATOR_OUTPUT_STATUS function payload_fns.payload_375(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 140 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 140) @@ -38610,78 +49037,112 @@ function payload_fns.payload_375(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_active, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_0, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_1, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_2, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_3, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_4, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_5, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_6, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_7, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_8, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_9, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_10, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_11, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_12, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_13, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_14, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_15, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_16, padded(field_offset, 4)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_17, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_18, padded(field_offset, 4)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_19, padded(field_offset, 4)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_20, padded(field_offset, 4)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_21, padded(field_offset, 4)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_22, padded(field_offset, 4)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_23, padded(field_offset, 4)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_24, padded(field_offset, 4)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_25, padded(field_offset, 4)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_26, padded(field_offset, 4)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_27, padded(field_offset, 4)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_28, padded(field_offset, 4)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_29, padded(field_offset, 4)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_30, padded(field_offset, 4)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_31, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_active, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_0, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_1, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_2, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_3, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_4, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_5, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_6, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_7, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_8, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_9, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_10, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_11, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_12, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_13, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_14, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_15, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_16, tvbrange, value) + tvbrange = padded(offset + 80, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_17, tvbrange, value) + tvbrange = padded(offset + 84, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_18, tvbrange, value) + tvbrange = padded(offset + 88, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_19, tvbrange, value) + tvbrange = padded(offset + 92, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_20, tvbrange, value) + tvbrange = padded(offset + 96, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_21, tvbrange, value) + tvbrange = padded(offset + 100, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_22, tvbrange, value) + tvbrange = padded(offset + 104, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_23, tvbrange, value) + tvbrange = padded(offset + 108, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_24, tvbrange, value) + tvbrange = padded(offset + 112, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_25, tvbrange, value) + tvbrange = padded(offset + 116, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_26, tvbrange, value) + tvbrange = padded(offset + 120, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_27, tvbrange, value) + tvbrange = padded(offset + 124, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_28, tvbrange, value) + tvbrange = padded(offset + 128, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_29, tvbrange, value) + tvbrange = padded(offset + 132, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_30, tvbrange, value) + tvbrange = padded(offset + 136, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_31, tvbrange, value) end -- dissect payload of message type TUNNEL function payload_fns.payload_385(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 133 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 133) @@ -38689,274 +49150,406 @@ function payload_fns.payload_385(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.TUNNEL_target_system, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.TUNNEL_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.TUNNEL_payload_type, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.TUNNEL_payload_length, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.TUNNEL_payload_0, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.TUNNEL_payload_1, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.TUNNEL_payload_2, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.TUNNEL_payload_3, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.TUNNEL_payload_4, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.TUNNEL_payload_5, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.TUNNEL_payload_6, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.TUNNEL_payload_7, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.TUNNEL_payload_8, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.TUNNEL_payload_9, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.TUNNEL_payload_10, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.TUNNEL_payload_11, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.TUNNEL_payload_12, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.TUNNEL_payload_13, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.TUNNEL_payload_14, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.TUNNEL_payload_15, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.TUNNEL_payload_16, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.TUNNEL_payload_17, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.TUNNEL_payload_18, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.TUNNEL_payload_19, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.TUNNEL_payload_20, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.TUNNEL_payload_21, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.TUNNEL_payload_22, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.TUNNEL_payload_23, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.TUNNEL_payload_24, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.TUNNEL_payload_25, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.TUNNEL_payload_26, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.TUNNEL_payload_27, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.TUNNEL_payload_28, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.TUNNEL_payload_29, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.TUNNEL_payload_30, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.TUNNEL_payload_31, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.TUNNEL_payload_32, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.TUNNEL_payload_33, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.TUNNEL_payload_34, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.TUNNEL_payload_35, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.TUNNEL_payload_36, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.TUNNEL_payload_37, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.TUNNEL_payload_38, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.TUNNEL_payload_39, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.TUNNEL_payload_40, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.TUNNEL_payload_41, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.TUNNEL_payload_42, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.TUNNEL_payload_43, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.TUNNEL_payload_44, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.TUNNEL_payload_45, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.TUNNEL_payload_46, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.TUNNEL_payload_47, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.TUNNEL_payload_48, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.TUNNEL_payload_49, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.TUNNEL_payload_50, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.TUNNEL_payload_51, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.TUNNEL_payload_52, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.TUNNEL_payload_53, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.TUNNEL_payload_54, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.TUNNEL_payload_55, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.TUNNEL_payload_56, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.TUNNEL_payload_57, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.TUNNEL_payload_58, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.TUNNEL_payload_59, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.TUNNEL_payload_60, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.TUNNEL_payload_61, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.TUNNEL_payload_62, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.TUNNEL_payload_63, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.TUNNEL_payload_64, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.TUNNEL_payload_65, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.TUNNEL_payload_66, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.TUNNEL_payload_67, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.TUNNEL_payload_68, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.TUNNEL_payload_69, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.TUNNEL_payload_70, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.TUNNEL_payload_71, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.TUNNEL_payload_72, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.TUNNEL_payload_73, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.TUNNEL_payload_74, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.TUNNEL_payload_75, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.TUNNEL_payload_76, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.TUNNEL_payload_77, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.TUNNEL_payload_78, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.TUNNEL_payload_79, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.TUNNEL_payload_80, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.TUNNEL_payload_81, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.TUNNEL_payload_82, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.TUNNEL_payload_83, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.TUNNEL_payload_84, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.TUNNEL_payload_85, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.TUNNEL_payload_86, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.TUNNEL_payload_87, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.TUNNEL_payload_88, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.TUNNEL_payload_89, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.TUNNEL_payload_90, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.TUNNEL_payload_91, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.TUNNEL_payload_92, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.TUNNEL_payload_93, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.TUNNEL_payload_94, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.TUNNEL_payload_95, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.TUNNEL_payload_96, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.TUNNEL_payload_97, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.TUNNEL_payload_98, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.TUNNEL_payload_99, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.TUNNEL_payload_100, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.TUNNEL_payload_101, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.TUNNEL_payload_102, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.TUNNEL_payload_103, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.TUNNEL_payload_104, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.TUNNEL_payload_105, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.TUNNEL_payload_106, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.TUNNEL_payload_107, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.TUNNEL_payload_108, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.TUNNEL_payload_109, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.TUNNEL_payload_110, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.TUNNEL_payload_111, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.TUNNEL_payload_112, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.TUNNEL_payload_113, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.TUNNEL_payload_114, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.TUNNEL_payload_115, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.TUNNEL_payload_116, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.TUNNEL_payload_117, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.TUNNEL_payload_118, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.TUNNEL_payload_119, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.TUNNEL_payload_120, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.TUNNEL_payload_121, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.TUNNEL_payload_122, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.TUNNEL_payload_123, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.TUNNEL_payload_124, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.TUNNEL_payload_125, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.TUNNEL_payload_126, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.TUNNEL_payload_127, padded(field_offset, 1)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_target_system, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_type, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_length, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_0, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_1, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_2, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_3, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_4, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_5, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_6, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_7, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_8, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_9, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_10, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_11, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_12, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_13, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_14, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_15, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_16, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_17, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_18, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_19, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_20, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_21, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_22, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_23, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_24, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_25, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_26, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_27, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_28, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_29, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_30, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_31, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_32, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_33, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_34, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_35, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_36, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_37, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_38, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_39, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_40, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_41, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_42, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_43, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_44, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_45, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_46, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_47, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_48, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_49, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_50, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_51, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_52, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_53, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_54, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_55, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_56, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_57, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_58, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_59, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_60, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_61, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_62, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_63, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_64, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_65, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_66, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_67, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_68, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_69, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_70, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_71, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_72, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_73, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_74, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_75, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_76, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_77, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_78, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_79, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_80, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_81, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_82, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_83, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_84, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_85, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_86, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_87, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_88, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_89, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_90, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_91, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_92, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_93, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_94, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_95, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_96, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_97, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_98, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_99, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_100, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_101, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_102, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_103, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_104, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_105, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_106, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_107, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_108, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_109, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_110, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_111, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_112, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_113, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_114, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_115, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_116, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_117, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_118, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_119, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_120, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_121, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_122, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_123, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_124, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_125, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_126, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.TUNNEL_payload_127, tvbrange, value) end -- dissect payload of message type CAN_FRAME function payload_fns.payload_386(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 16 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 16) @@ -38964,36 +49557,49 @@ function payload_fns.payload_386(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAN_FRAME_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.CAN_FRAME_target_component, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.CAN_FRAME_bus, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.CAN_FRAME_len, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAN_FRAME_id, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAN_FRAME_data_0, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.CAN_FRAME_data_1, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.CAN_FRAME_data_2, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.CAN_FRAME_data_3, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAN_FRAME_data_4, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.CAN_FRAME_data_5, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.CAN_FRAME_data_6, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.CAN_FRAME_data_7, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_target_component, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_bus, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_len, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_id, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_0, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_1, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_2, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_3, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_4, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_5, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_6, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FRAME_data_7, tvbrange, value) end -- dissect payload of message type CANFD_FRAME function payload_fns.payload_387(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 72 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 72) @@ -39001,148 +49607,217 @@ function payload_fns.payload_387(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.CANFD_FRAME_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.CANFD_FRAME_target_component, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.CANFD_FRAME_bus, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.CANFD_FRAME_len, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CANFD_FRAME_id, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CANFD_FRAME_data_0, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.CANFD_FRAME_data_1, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.CANFD_FRAME_data_2, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.CANFD_FRAME_data_3, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CANFD_FRAME_data_4, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.CANFD_FRAME_data_5, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.CANFD_FRAME_data_6, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.CANFD_FRAME_data_7, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CANFD_FRAME_data_8, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.CANFD_FRAME_data_9, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.CANFD_FRAME_data_10, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.CANFD_FRAME_data_11, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CANFD_FRAME_data_12, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.CANFD_FRAME_data_13, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.CANFD_FRAME_data_14, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.CANFD_FRAME_data_15, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CANFD_FRAME_data_16, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.CANFD_FRAME_data_17, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.CANFD_FRAME_data_18, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.CANFD_FRAME_data_19, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CANFD_FRAME_data_20, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.CANFD_FRAME_data_21, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.CANFD_FRAME_data_22, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.CANFD_FRAME_data_23, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.CANFD_FRAME_data_24, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.CANFD_FRAME_data_25, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.CANFD_FRAME_data_26, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.CANFD_FRAME_data_27, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CANFD_FRAME_data_28, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.CANFD_FRAME_data_29, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.CANFD_FRAME_data_30, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.CANFD_FRAME_data_31, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.CANFD_FRAME_data_32, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.CANFD_FRAME_data_33, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.CANFD_FRAME_data_34, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.CANFD_FRAME_data_35, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.CANFD_FRAME_data_36, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.CANFD_FRAME_data_37, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.CANFD_FRAME_data_38, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.CANFD_FRAME_data_39, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.CANFD_FRAME_data_40, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.CANFD_FRAME_data_41, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.CANFD_FRAME_data_42, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.CANFD_FRAME_data_43, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.CANFD_FRAME_data_44, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.CANFD_FRAME_data_45, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.CANFD_FRAME_data_46, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.CANFD_FRAME_data_47, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.CANFD_FRAME_data_48, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.CANFD_FRAME_data_49, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.CANFD_FRAME_data_50, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.CANFD_FRAME_data_51, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.CANFD_FRAME_data_52, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.CANFD_FRAME_data_53, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.CANFD_FRAME_data_54, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.CANFD_FRAME_data_55, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.CANFD_FRAME_data_56, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.CANFD_FRAME_data_57, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.CANFD_FRAME_data_58, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.CANFD_FRAME_data_59, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.CANFD_FRAME_data_60, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.CANFD_FRAME_data_61, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.CANFD_FRAME_data_62, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.CANFD_FRAME_data_63, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_target_component, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_bus, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_len, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_id, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_0, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_1, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_2, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_3, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_4, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_5, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_6, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_7, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_8, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_9, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_10, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_11, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_12, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_13, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_14, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_15, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_16, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_17, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_18, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_19, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_20, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_21, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_22, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_23, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_24, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_25, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_26, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_27, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_28, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_29, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_30, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_31, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_32, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_33, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_34, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_35, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_36, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_37, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_38, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_39, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_40, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_41, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_42, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_43, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_44, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_45, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_46, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_47, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_48, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_49, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_50, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_51, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_52, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_53, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_54, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_55, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_56, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_57, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_58, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_59, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_60, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_61, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_62, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CANFD_FRAME_data_63, tvbrange, value) end -- dissect payload of message type CAN_FILTER_MODIFY function payload_fns.payload_388(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 37 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 37) @@ -39150,52 +49825,73 @@ function payload_fns.payload_388(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 32 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_target_system, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_target_component, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_bus, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_operation, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_num_ids, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_0, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_1, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_2, padded(field_offset, 2)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_3, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_4, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_5, padded(field_offset, 2)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_6, padded(field_offset, 2)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_7, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_8, padded(field_offset, 2)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_9, padded(field_offset, 2)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_10, padded(field_offset, 2)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_11, padded(field_offset, 2)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_12, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_13, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_14, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.CAN_FILTER_MODIFY_ids_15, padded(field_offset, 2)) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_target_system, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_target_component, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_bus, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_operation, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_num_ids, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_0, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_1, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_2, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_3, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_4, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_5, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_6, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_7, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_8, tvbrange, value) + tvbrange = padded(offset + 18, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_9, tvbrange, value) + tvbrange = padded(offset + 20, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_10, tvbrange, value) + tvbrange = padded(offset + 22, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_11, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_12, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_13, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_14, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAN_FILTER_MODIFY_ids_15, tvbrange, value) end -- dissect payload of message type WHEEL_DISTANCE function payload_fns.payload_9000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 137 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 137) @@ -39203,46 +49899,64 @@ function payload_fns.payload_9000(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_time_usec, padded(field_offset, 8)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_count, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_0, padded(field_offset, 8)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_1, padded(field_offset, 8)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_2, padded(field_offset, 8)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_3, padded(field_offset, 8)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_4, padded(field_offset, 8)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_5, padded(field_offset, 8)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_6, padded(field_offset, 8)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_7, padded(field_offset, 8)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_8, padded(field_offset, 8)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_9, padded(field_offset, 8)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_10, padded(field_offset, 8)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_11, padded(field_offset, 8)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_12, padded(field_offset, 8)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_13, padded(field_offset, 8)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_14, padded(field_offset, 8)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.WHEEL_DISTANCE_distance_15, padded(field_offset, 8)) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.WHEEL_DISTANCE_time_usec, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.WHEEL_DISTANCE_count, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_0, tvbrange, value) + tvbrange = padded(offset + 16, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_1, tvbrange, value) + tvbrange = padded(offset + 24, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_2, tvbrange, value) + tvbrange = padded(offset + 32, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_3, tvbrange, value) + tvbrange = padded(offset + 40, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_4, tvbrange, value) + tvbrange = padded(offset + 48, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_5, tvbrange, value) + tvbrange = padded(offset + 56, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_6, tvbrange, value) + tvbrange = padded(offset + 64, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_7, tvbrange, value) + tvbrange = padded(offset + 72, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_8, tvbrange, value) + tvbrange = padded(offset + 80, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_9, tvbrange, value) + tvbrange = padded(offset + 88, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_10, tvbrange, value) + tvbrange = padded(offset + 96, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_11, tvbrange, value) + tvbrange = padded(offset + 104, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_12, tvbrange, value) + tvbrange = padded(offset + 112, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_13, tvbrange, value) + tvbrange = padded(offset + 120, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_14, tvbrange, value) + tvbrange = padded(offset + 128, 8) + value = tvbrange:le_double() + subtree = tree:add_le(f.WHEEL_DISTANCE_distance_15, tvbrange, value) end -- dissect payload of message type WINCH_STATUS function payload_fns.payload_9005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 34 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 34) @@ -39250,27 +49964,35 @@ function payload_fns.payload_9005(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.WINCH_STATUS_time_usec, padded(field_offset, 8)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.WINCH_STATUS_line_length, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.WINCH_STATUS_speed, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.WINCH_STATUS_tension, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.WINCH_STATUS_voltage, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.WINCH_STATUS_current, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.WINCH_STATUS_temperature, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.WINCH_STATUS_status, padded(field_offset, 4)) - dissect_flags_MAV_WINCH_STATUS_FLAG(subtree, "WINCH_STATUS_status", value) + tvbrange = padded(offset + 0, 8) + value = tvbrange:le_uint64() + subtree = tree:add_le(f.WINCH_STATUS_time_usec, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WINCH_STATUS_line_length, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WINCH_STATUS_speed, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WINCH_STATUS_tension, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WINCH_STATUS_voltage, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.WINCH_STATUS_current, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.WINCH_STATUS_temperature, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.WINCH_STATUS_status, tvbrange, value) + dissect_flags_MAV_WINCH_STATUS_FLAG(subtree, "WINCH_STATUS_status", tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_BASIC_ID function payload_fns.payload_12900(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 44 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 44) @@ -39278,98 +50000,142 @@ function payload_fns.payload_12900(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_type, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_ua_type, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_0, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_1, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_2, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_3, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_4, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_5, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_6, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_7, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_8, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_9, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_10, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_11, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_12, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_13, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_14, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_15, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_16, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_17, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_18, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_19, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_id_type, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_ua_type, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_0, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_1, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_2, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_3, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_4, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_5, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_6, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_7, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_8, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_9, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_10, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_11, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_12, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_13, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_14, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_15, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_16, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_17, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_18, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_BASIC_ID_uas_id_19, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_LOCATION function payload_fns.payload_12901(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 59 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 59) @@ -39377,86 +50143,124 @@ function payload_fns.payload_12901(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 30 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_target_system, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_target_component, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_status, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_direction, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_speed_horizontal, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_speed_vertical, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_longitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_altitude_barometric, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_altitude_geodetic, padded(field_offset, 4)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_height_reference, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_height, padded(field_offset, 4)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_horizontal_accuracy, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_vertical_accuracy, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_barometer_accuracy, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_speed_accuracy, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_timestamp, padded(field_offset, 4)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_LOCATION_timestamp_accuracy, padded(field_offset, 1)) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_target_system, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_target_component, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_status, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_direction, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_speed_horizontal, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_speed_vertical, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_altitude_barometric, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_altitude_geodetic, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_height_reference, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_height, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_horizontal_accuracy, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_vertical_accuracy, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_barometer_accuracy, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_speed_accuracy, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_timestamp, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_LOCATION_timestamp_accuracy, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_AUTHENTICATION function payload_fns.payload_12902(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 53 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 53) @@ -39464,110 +50268,160 @@ function payload_fns.payload_12902(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_target_component, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_type, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_data_page, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_last_page_index, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_length, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_timestamp, padded(field_offset, 4)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_0, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_1, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_2, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_3, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_4, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_5, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_6, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_7, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_8, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_9, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_10, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_11, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_12, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_13, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_14, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_15, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_16, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_17, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_18, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_19, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_20, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_21, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_22, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_target_component, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_type, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_data_page, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_last_page_index, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_length, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_timestamp, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_0, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_1, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_2, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_3, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_4, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_5, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_6, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_7, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_8, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_9, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_10, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_11, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_12, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_13, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_14, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_15, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_16, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_17, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_18, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_19, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_20, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_21, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_AUTHENTICATION_authentication_data_22, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_SELF_ID function payload_fns.payload_12903(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 46 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 46) @@ -39575,58 +50429,82 @@ function payload_fns.payload_12903(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_description_type, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_description, padded(field_offset, 23)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_description_type, tvbrange, value) + tvbrange = padded(offset + 23, 23) + value = tvbrange:string() + subtree = tree:add_le(f.OPEN_DRONE_ID_SELF_ID_description, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_SYSTEM function payload_fns.payload_12904(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 54 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 54) @@ -39634,78 +50512,112 @@ function payload_fns.payload_12904(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 28 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_target_system, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_target_component, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_location_type, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_classification_type, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_longitude, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_count, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_radius, padded(field_offset, 2)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_ceiling, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_floor, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_category_eu, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_class_eu, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_altitude_geo, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_timestamp, padded(field_offset, 4)) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_target_system, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_target_component, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_location_type, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_classification_type, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_longitude, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_count, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_radius, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_ceiling, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_area_floor, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_category_eu, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_class_eu, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_operator_altitude_geo, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_timestamp, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_OPERATOR_ID function payload_fns.payload_12905(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 43 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 43) @@ -39713,58 +50625,82 @@ function payload_fns.payload_12905(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_operator_id_type, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_operator_id, padded(field_offset, 20)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_operator_id_type, tvbrange, value) + tvbrange = padded(offset + 23, 20) + value = tvbrange:string() + subtree = tree:add_le(f.OPEN_DRONE_ID_OPERATOR_ID_operator_id, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_ARM_STATUS function payload_fns.payload_12918(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 51 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 51) @@ -39772,14 +50708,16 @@ function payload_fns.payload_12918(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_ARM_STATUS_status, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_ARM_STATUS_error, padded(field_offset, 50)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_ARM_STATUS_status, tvbrange, value) + tvbrange = padded(offset + 1, 50) + value = tvbrange:string() + subtree = tree:add_le(f.OPEN_DRONE_ID_ARM_STATUS_error, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_MESSAGE_PACK function payload_fns.payload_12915(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 249 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 249) @@ -39787,508 +50725,757 @@ function payload_fns.payload_12915(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_target_system, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_target_component, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_0, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_1, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_2, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_3, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_4, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_5, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_6, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_7, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_8, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_9, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_10, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_11, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_12, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_13, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_14, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_15, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_16, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_17, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_18, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_19, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_single_message_size, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_msg_pack_size, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_0, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_1, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_2, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_3, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_4, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_5, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_6, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_7, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_8, padded(field_offset, 1)) - field_offset = offset + 33 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_9, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_10, padded(field_offset, 1)) - field_offset = offset + 35 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_11, padded(field_offset, 1)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_12, padded(field_offset, 1)) - field_offset = offset + 37 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_13, padded(field_offset, 1)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_14, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_15, padded(field_offset, 1)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_16, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_17, padded(field_offset, 1)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_18, padded(field_offset, 1)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_19, padded(field_offset, 1)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_20, padded(field_offset, 1)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_21, padded(field_offset, 1)) - field_offset = offset + 46 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_22, padded(field_offset, 1)) - field_offset = offset + 47 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_23, padded(field_offset, 1)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_24, padded(field_offset, 1)) - field_offset = offset + 49 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_25, padded(field_offset, 1)) - field_offset = offset + 50 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_26, padded(field_offset, 1)) - field_offset = offset + 51 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_27, padded(field_offset, 1)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_28, padded(field_offset, 1)) - field_offset = offset + 53 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_29, padded(field_offset, 1)) - field_offset = offset + 54 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_30, padded(field_offset, 1)) - field_offset = offset + 55 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_31, padded(field_offset, 1)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_32, padded(field_offset, 1)) - field_offset = offset + 57 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_33, padded(field_offset, 1)) - field_offset = offset + 58 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_34, padded(field_offset, 1)) - field_offset = offset + 59 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_35, padded(field_offset, 1)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_36, padded(field_offset, 1)) - field_offset = offset + 61 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_37, padded(field_offset, 1)) - field_offset = offset + 62 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_38, padded(field_offset, 1)) - field_offset = offset + 63 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_39, padded(field_offset, 1)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_40, padded(field_offset, 1)) - field_offset = offset + 65 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_41, padded(field_offset, 1)) - field_offset = offset + 66 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_42, padded(field_offset, 1)) - field_offset = offset + 67 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_43, padded(field_offset, 1)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_44, padded(field_offset, 1)) - field_offset = offset + 69 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_45, padded(field_offset, 1)) - field_offset = offset + 70 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_46, padded(field_offset, 1)) - field_offset = offset + 71 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_47, padded(field_offset, 1)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_48, padded(field_offset, 1)) - field_offset = offset + 73 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_49, padded(field_offset, 1)) - field_offset = offset + 74 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_50, padded(field_offset, 1)) - field_offset = offset + 75 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_51, padded(field_offset, 1)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_52, padded(field_offset, 1)) - field_offset = offset + 77 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_53, padded(field_offset, 1)) - field_offset = offset + 78 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_54, padded(field_offset, 1)) - field_offset = offset + 79 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_55, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_56, padded(field_offset, 1)) - field_offset = offset + 81 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_57, padded(field_offset, 1)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_58, padded(field_offset, 1)) - field_offset = offset + 83 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_59, padded(field_offset, 1)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_60, padded(field_offset, 1)) - field_offset = offset + 85 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_61, padded(field_offset, 1)) - field_offset = offset + 86 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_62, padded(field_offset, 1)) - field_offset = offset + 87 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_63, padded(field_offset, 1)) - field_offset = offset + 88 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_64, padded(field_offset, 1)) - field_offset = offset + 89 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_65, padded(field_offset, 1)) - field_offset = offset + 90 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_66, padded(field_offset, 1)) - field_offset = offset + 91 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_67, padded(field_offset, 1)) - field_offset = offset + 92 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_68, padded(field_offset, 1)) - field_offset = offset + 93 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_69, padded(field_offset, 1)) - field_offset = offset + 94 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_70, padded(field_offset, 1)) - field_offset = offset + 95 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_71, padded(field_offset, 1)) - field_offset = offset + 96 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_72, padded(field_offset, 1)) - field_offset = offset + 97 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_73, padded(field_offset, 1)) - field_offset = offset + 98 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_74, padded(field_offset, 1)) - field_offset = offset + 99 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_75, padded(field_offset, 1)) - field_offset = offset + 100 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_76, padded(field_offset, 1)) - field_offset = offset + 101 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_77, padded(field_offset, 1)) - field_offset = offset + 102 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_78, padded(field_offset, 1)) - field_offset = offset + 103 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_79, padded(field_offset, 1)) - field_offset = offset + 104 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_80, padded(field_offset, 1)) - field_offset = offset + 105 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_81, padded(field_offset, 1)) - field_offset = offset + 106 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_82, padded(field_offset, 1)) - field_offset = offset + 107 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_83, padded(field_offset, 1)) - field_offset = offset + 108 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_84, padded(field_offset, 1)) - field_offset = offset + 109 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_85, padded(field_offset, 1)) - field_offset = offset + 110 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_86, padded(field_offset, 1)) - field_offset = offset + 111 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_87, padded(field_offset, 1)) - field_offset = offset + 112 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_88, padded(field_offset, 1)) - field_offset = offset + 113 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_89, padded(field_offset, 1)) - field_offset = offset + 114 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_90, padded(field_offset, 1)) - field_offset = offset + 115 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_91, padded(field_offset, 1)) - field_offset = offset + 116 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_92, padded(field_offset, 1)) - field_offset = offset + 117 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_93, padded(field_offset, 1)) - field_offset = offset + 118 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_94, padded(field_offset, 1)) - field_offset = offset + 119 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_95, padded(field_offset, 1)) - field_offset = offset + 120 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_96, padded(field_offset, 1)) - field_offset = offset + 121 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_97, padded(field_offset, 1)) - field_offset = offset + 122 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_98, padded(field_offset, 1)) - field_offset = offset + 123 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_99, padded(field_offset, 1)) - field_offset = offset + 124 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_100, padded(field_offset, 1)) - field_offset = offset + 125 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_101, padded(field_offset, 1)) - field_offset = offset + 126 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_102, padded(field_offset, 1)) - field_offset = offset + 127 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_103, padded(field_offset, 1)) - field_offset = offset + 128 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_104, padded(field_offset, 1)) - field_offset = offset + 129 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_105, padded(field_offset, 1)) - field_offset = offset + 130 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_106, padded(field_offset, 1)) - field_offset = offset + 131 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_107, padded(field_offset, 1)) - field_offset = offset + 132 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_108, padded(field_offset, 1)) - field_offset = offset + 133 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_109, padded(field_offset, 1)) - field_offset = offset + 134 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_110, padded(field_offset, 1)) - field_offset = offset + 135 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_111, padded(field_offset, 1)) - field_offset = offset + 136 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_112, padded(field_offset, 1)) - field_offset = offset + 137 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_113, padded(field_offset, 1)) - field_offset = offset + 138 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_114, padded(field_offset, 1)) - field_offset = offset + 139 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_115, padded(field_offset, 1)) - field_offset = offset + 140 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_116, padded(field_offset, 1)) - field_offset = offset + 141 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_117, padded(field_offset, 1)) - field_offset = offset + 142 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_118, padded(field_offset, 1)) - field_offset = offset + 143 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_119, padded(field_offset, 1)) - field_offset = offset + 144 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_120, padded(field_offset, 1)) - field_offset = offset + 145 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_121, padded(field_offset, 1)) - field_offset = offset + 146 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_122, padded(field_offset, 1)) - field_offset = offset + 147 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_123, padded(field_offset, 1)) - field_offset = offset + 148 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_124, padded(field_offset, 1)) - field_offset = offset + 149 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_125, padded(field_offset, 1)) - field_offset = offset + 150 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_126, padded(field_offset, 1)) - field_offset = offset + 151 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_127, padded(field_offset, 1)) - field_offset = offset + 152 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_128, padded(field_offset, 1)) - field_offset = offset + 153 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_129, padded(field_offset, 1)) - field_offset = offset + 154 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_130, padded(field_offset, 1)) - field_offset = offset + 155 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_131, padded(field_offset, 1)) - field_offset = offset + 156 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_132, padded(field_offset, 1)) - field_offset = offset + 157 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_133, padded(field_offset, 1)) - field_offset = offset + 158 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_134, padded(field_offset, 1)) - field_offset = offset + 159 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_135, padded(field_offset, 1)) - field_offset = offset + 160 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_136, padded(field_offset, 1)) - field_offset = offset + 161 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_137, padded(field_offset, 1)) - field_offset = offset + 162 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_138, padded(field_offset, 1)) - field_offset = offset + 163 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_139, padded(field_offset, 1)) - field_offset = offset + 164 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_140, padded(field_offset, 1)) - field_offset = offset + 165 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_141, padded(field_offset, 1)) - field_offset = offset + 166 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_142, padded(field_offset, 1)) - field_offset = offset + 167 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_143, padded(field_offset, 1)) - field_offset = offset + 168 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_144, padded(field_offset, 1)) - field_offset = offset + 169 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_145, padded(field_offset, 1)) - field_offset = offset + 170 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_146, padded(field_offset, 1)) - field_offset = offset + 171 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_147, padded(field_offset, 1)) - field_offset = offset + 172 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_148, padded(field_offset, 1)) - field_offset = offset + 173 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_149, padded(field_offset, 1)) - field_offset = offset + 174 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_150, padded(field_offset, 1)) - field_offset = offset + 175 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_151, padded(field_offset, 1)) - field_offset = offset + 176 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_152, padded(field_offset, 1)) - field_offset = offset + 177 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_153, padded(field_offset, 1)) - field_offset = offset + 178 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_154, padded(field_offset, 1)) - field_offset = offset + 179 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_155, padded(field_offset, 1)) - field_offset = offset + 180 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_156, padded(field_offset, 1)) - field_offset = offset + 181 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_157, padded(field_offset, 1)) - field_offset = offset + 182 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_158, padded(field_offset, 1)) - field_offset = offset + 183 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_159, padded(field_offset, 1)) - field_offset = offset + 184 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_160, padded(field_offset, 1)) - field_offset = offset + 185 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_161, padded(field_offset, 1)) - field_offset = offset + 186 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_162, padded(field_offset, 1)) - field_offset = offset + 187 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_163, padded(field_offset, 1)) - field_offset = offset + 188 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_164, padded(field_offset, 1)) - field_offset = offset + 189 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_165, padded(field_offset, 1)) - field_offset = offset + 190 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_166, padded(field_offset, 1)) - field_offset = offset + 191 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_167, padded(field_offset, 1)) - field_offset = offset + 192 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_168, padded(field_offset, 1)) - field_offset = offset + 193 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_169, padded(field_offset, 1)) - field_offset = offset + 194 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_170, padded(field_offset, 1)) - field_offset = offset + 195 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_171, padded(field_offset, 1)) - field_offset = offset + 196 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_172, padded(field_offset, 1)) - field_offset = offset + 197 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_173, padded(field_offset, 1)) - field_offset = offset + 198 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_174, padded(field_offset, 1)) - field_offset = offset + 199 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_175, padded(field_offset, 1)) - field_offset = offset + 200 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_176, padded(field_offset, 1)) - field_offset = offset + 201 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_177, padded(field_offset, 1)) - field_offset = offset + 202 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_178, padded(field_offset, 1)) - field_offset = offset + 203 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_179, padded(field_offset, 1)) - field_offset = offset + 204 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_180, padded(field_offset, 1)) - field_offset = offset + 205 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_181, padded(field_offset, 1)) - field_offset = offset + 206 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_182, padded(field_offset, 1)) - field_offset = offset + 207 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_183, padded(field_offset, 1)) - field_offset = offset + 208 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_184, padded(field_offset, 1)) - field_offset = offset + 209 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_185, padded(field_offset, 1)) - field_offset = offset + 210 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_186, padded(field_offset, 1)) - field_offset = offset + 211 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_187, padded(field_offset, 1)) - field_offset = offset + 212 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_188, padded(field_offset, 1)) - field_offset = offset + 213 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_189, padded(field_offset, 1)) - field_offset = offset + 214 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_190, padded(field_offset, 1)) - field_offset = offset + 215 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_191, padded(field_offset, 1)) - field_offset = offset + 216 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_192, padded(field_offset, 1)) - field_offset = offset + 217 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_193, padded(field_offset, 1)) - field_offset = offset + 218 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_194, padded(field_offset, 1)) - field_offset = offset + 219 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_195, padded(field_offset, 1)) - field_offset = offset + 220 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_196, padded(field_offset, 1)) - field_offset = offset + 221 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_197, padded(field_offset, 1)) - field_offset = offset + 222 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_198, padded(field_offset, 1)) - field_offset = offset + 223 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_199, padded(field_offset, 1)) - field_offset = offset + 224 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_200, padded(field_offset, 1)) - field_offset = offset + 225 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_201, padded(field_offset, 1)) - field_offset = offset + 226 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_202, padded(field_offset, 1)) - field_offset = offset + 227 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_203, padded(field_offset, 1)) - field_offset = offset + 228 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_204, padded(field_offset, 1)) - field_offset = offset + 229 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_205, padded(field_offset, 1)) - field_offset = offset + 230 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_206, padded(field_offset, 1)) - field_offset = offset + 231 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_207, padded(field_offset, 1)) - field_offset = offset + 232 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_208, padded(field_offset, 1)) - field_offset = offset + 233 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_209, padded(field_offset, 1)) - field_offset = offset + 234 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_210, padded(field_offset, 1)) - field_offset = offset + 235 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_211, padded(field_offset, 1)) - field_offset = offset + 236 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_212, padded(field_offset, 1)) - field_offset = offset + 237 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_213, padded(field_offset, 1)) - field_offset = offset + 238 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_214, padded(field_offset, 1)) - field_offset = offset + 239 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_215, padded(field_offset, 1)) - field_offset = offset + 240 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_216, padded(field_offset, 1)) - field_offset = offset + 241 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_217, padded(field_offset, 1)) - field_offset = offset + 242 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_218, padded(field_offset, 1)) - field_offset = offset + 243 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_219, padded(field_offset, 1)) - field_offset = offset + 244 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_220, padded(field_offset, 1)) - field_offset = offset + 245 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_221, padded(field_offset, 1)) - field_offset = offset + 246 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_222, padded(field_offset, 1)) - field_offset = offset + 247 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_223, padded(field_offset, 1)) - field_offset = offset + 248 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_224, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_target_system, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_target_component, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_0, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_1, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_2, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_3, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_4, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_5, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_6, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_7, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_8, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_9, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_10, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_11, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_12, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_13, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_14, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_15, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_16, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_17, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_18, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_id_or_mac_19, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_single_message_size, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_msg_pack_size, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_0, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_1, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_2, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_3, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_4, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_5, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_6, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_7, tvbrange, value) + tvbrange = padded(offset + 32, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_8, tvbrange, value) + tvbrange = padded(offset + 33, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_9, tvbrange, value) + tvbrange = padded(offset + 34, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_10, tvbrange, value) + tvbrange = padded(offset + 35, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_11, tvbrange, value) + tvbrange = padded(offset + 36, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_12, tvbrange, value) + tvbrange = padded(offset + 37, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_13, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_14, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_15, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_16, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_17, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_18, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_19, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_20, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_21, tvbrange, value) + tvbrange = padded(offset + 46, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_22, tvbrange, value) + tvbrange = padded(offset + 47, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_23, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_24, tvbrange, value) + tvbrange = padded(offset + 49, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_25, tvbrange, value) + tvbrange = padded(offset + 50, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_26, tvbrange, value) + tvbrange = padded(offset + 51, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_27, tvbrange, value) + tvbrange = padded(offset + 52, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_28, tvbrange, value) + tvbrange = padded(offset + 53, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_29, tvbrange, value) + tvbrange = padded(offset + 54, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_30, tvbrange, value) + tvbrange = padded(offset + 55, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_31, tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_32, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_33, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_34, tvbrange, value) + tvbrange = padded(offset + 59, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_35, tvbrange, value) + tvbrange = padded(offset + 60, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_36, tvbrange, value) + tvbrange = padded(offset + 61, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_37, tvbrange, value) + tvbrange = padded(offset + 62, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_38, tvbrange, value) + tvbrange = padded(offset + 63, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_39, tvbrange, value) + tvbrange = padded(offset + 64, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_40, tvbrange, value) + tvbrange = padded(offset + 65, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_41, tvbrange, value) + tvbrange = padded(offset + 66, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_42, tvbrange, value) + tvbrange = padded(offset + 67, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_43, tvbrange, value) + tvbrange = padded(offset + 68, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_44, tvbrange, value) + tvbrange = padded(offset + 69, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_45, tvbrange, value) + tvbrange = padded(offset + 70, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_46, tvbrange, value) + tvbrange = padded(offset + 71, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_47, tvbrange, value) + tvbrange = padded(offset + 72, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_48, tvbrange, value) + tvbrange = padded(offset + 73, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_49, tvbrange, value) + tvbrange = padded(offset + 74, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_50, tvbrange, value) + tvbrange = padded(offset + 75, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_51, tvbrange, value) + tvbrange = padded(offset + 76, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_52, tvbrange, value) + tvbrange = padded(offset + 77, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_53, tvbrange, value) + tvbrange = padded(offset + 78, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_54, tvbrange, value) + tvbrange = padded(offset + 79, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_55, tvbrange, value) + tvbrange = padded(offset + 80, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_56, tvbrange, value) + tvbrange = padded(offset + 81, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_57, tvbrange, value) + tvbrange = padded(offset + 82, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_58, tvbrange, value) + tvbrange = padded(offset + 83, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_59, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_60, tvbrange, value) + tvbrange = padded(offset + 85, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_61, tvbrange, value) + tvbrange = padded(offset + 86, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_62, tvbrange, value) + tvbrange = padded(offset + 87, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_63, tvbrange, value) + tvbrange = padded(offset + 88, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_64, tvbrange, value) + tvbrange = padded(offset + 89, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_65, tvbrange, value) + tvbrange = padded(offset + 90, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_66, tvbrange, value) + tvbrange = padded(offset + 91, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_67, tvbrange, value) + tvbrange = padded(offset + 92, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_68, tvbrange, value) + tvbrange = padded(offset + 93, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_69, tvbrange, value) + tvbrange = padded(offset + 94, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_70, tvbrange, value) + tvbrange = padded(offset + 95, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_71, tvbrange, value) + tvbrange = padded(offset + 96, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_72, tvbrange, value) + tvbrange = padded(offset + 97, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_73, tvbrange, value) + tvbrange = padded(offset + 98, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_74, tvbrange, value) + tvbrange = padded(offset + 99, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_75, tvbrange, value) + tvbrange = padded(offset + 100, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_76, tvbrange, value) + tvbrange = padded(offset + 101, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_77, tvbrange, value) + tvbrange = padded(offset + 102, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_78, tvbrange, value) + tvbrange = padded(offset + 103, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_79, tvbrange, value) + tvbrange = padded(offset + 104, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_80, tvbrange, value) + tvbrange = padded(offset + 105, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_81, tvbrange, value) + tvbrange = padded(offset + 106, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_82, tvbrange, value) + tvbrange = padded(offset + 107, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_83, tvbrange, value) + tvbrange = padded(offset + 108, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_84, tvbrange, value) + tvbrange = padded(offset + 109, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_85, tvbrange, value) + tvbrange = padded(offset + 110, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_86, tvbrange, value) + tvbrange = padded(offset + 111, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_87, tvbrange, value) + tvbrange = padded(offset + 112, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_88, tvbrange, value) + tvbrange = padded(offset + 113, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_89, tvbrange, value) + tvbrange = padded(offset + 114, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_90, tvbrange, value) + tvbrange = padded(offset + 115, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_91, tvbrange, value) + tvbrange = padded(offset + 116, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_92, tvbrange, value) + tvbrange = padded(offset + 117, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_93, tvbrange, value) + tvbrange = padded(offset + 118, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_94, tvbrange, value) + tvbrange = padded(offset + 119, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_95, tvbrange, value) + tvbrange = padded(offset + 120, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_96, tvbrange, value) + tvbrange = padded(offset + 121, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_97, tvbrange, value) + tvbrange = padded(offset + 122, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_98, tvbrange, value) + tvbrange = padded(offset + 123, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_99, tvbrange, value) + tvbrange = padded(offset + 124, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_100, tvbrange, value) + tvbrange = padded(offset + 125, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_101, tvbrange, value) + tvbrange = padded(offset + 126, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_102, tvbrange, value) + tvbrange = padded(offset + 127, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_103, tvbrange, value) + tvbrange = padded(offset + 128, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_104, tvbrange, value) + tvbrange = padded(offset + 129, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_105, tvbrange, value) + tvbrange = padded(offset + 130, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_106, tvbrange, value) + tvbrange = padded(offset + 131, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_107, tvbrange, value) + tvbrange = padded(offset + 132, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_108, tvbrange, value) + tvbrange = padded(offset + 133, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_109, tvbrange, value) + tvbrange = padded(offset + 134, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_110, tvbrange, value) + tvbrange = padded(offset + 135, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_111, tvbrange, value) + tvbrange = padded(offset + 136, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_112, tvbrange, value) + tvbrange = padded(offset + 137, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_113, tvbrange, value) + tvbrange = padded(offset + 138, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_114, tvbrange, value) + tvbrange = padded(offset + 139, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_115, tvbrange, value) + tvbrange = padded(offset + 140, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_116, tvbrange, value) + tvbrange = padded(offset + 141, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_117, tvbrange, value) + tvbrange = padded(offset + 142, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_118, tvbrange, value) + tvbrange = padded(offset + 143, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_119, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_120, tvbrange, value) + tvbrange = padded(offset + 145, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_121, tvbrange, value) + tvbrange = padded(offset + 146, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_122, tvbrange, value) + tvbrange = padded(offset + 147, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_123, tvbrange, value) + tvbrange = padded(offset + 148, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_124, tvbrange, value) + tvbrange = padded(offset + 149, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_125, tvbrange, value) + tvbrange = padded(offset + 150, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_126, tvbrange, value) + tvbrange = padded(offset + 151, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_127, tvbrange, value) + tvbrange = padded(offset + 152, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_128, tvbrange, value) + tvbrange = padded(offset + 153, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_129, tvbrange, value) + tvbrange = padded(offset + 154, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_130, tvbrange, value) + tvbrange = padded(offset + 155, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_131, tvbrange, value) + tvbrange = padded(offset + 156, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_132, tvbrange, value) + tvbrange = padded(offset + 157, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_133, tvbrange, value) + tvbrange = padded(offset + 158, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_134, tvbrange, value) + tvbrange = padded(offset + 159, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_135, tvbrange, value) + tvbrange = padded(offset + 160, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_136, tvbrange, value) + tvbrange = padded(offset + 161, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_137, tvbrange, value) + tvbrange = padded(offset + 162, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_138, tvbrange, value) + tvbrange = padded(offset + 163, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_139, tvbrange, value) + tvbrange = padded(offset + 164, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_140, tvbrange, value) + tvbrange = padded(offset + 165, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_141, tvbrange, value) + tvbrange = padded(offset + 166, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_142, tvbrange, value) + tvbrange = padded(offset + 167, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_143, tvbrange, value) + tvbrange = padded(offset + 168, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_144, tvbrange, value) + tvbrange = padded(offset + 169, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_145, tvbrange, value) + tvbrange = padded(offset + 170, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_146, tvbrange, value) + tvbrange = padded(offset + 171, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_147, tvbrange, value) + tvbrange = padded(offset + 172, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_148, tvbrange, value) + tvbrange = padded(offset + 173, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_149, tvbrange, value) + tvbrange = padded(offset + 174, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_150, tvbrange, value) + tvbrange = padded(offset + 175, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_151, tvbrange, value) + tvbrange = padded(offset + 176, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_152, tvbrange, value) + tvbrange = padded(offset + 177, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_153, tvbrange, value) + tvbrange = padded(offset + 178, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_154, tvbrange, value) + tvbrange = padded(offset + 179, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_155, tvbrange, value) + tvbrange = padded(offset + 180, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_156, tvbrange, value) + tvbrange = padded(offset + 181, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_157, tvbrange, value) + tvbrange = padded(offset + 182, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_158, tvbrange, value) + tvbrange = padded(offset + 183, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_159, tvbrange, value) + tvbrange = padded(offset + 184, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_160, tvbrange, value) + tvbrange = padded(offset + 185, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_161, tvbrange, value) + tvbrange = padded(offset + 186, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_162, tvbrange, value) + tvbrange = padded(offset + 187, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_163, tvbrange, value) + tvbrange = padded(offset + 188, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_164, tvbrange, value) + tvbrange = padded(offset + 189, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_165, tvbrange, value) + tvbrange = padded(offset + 190, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_166, tvbrange, value) + tvbrange = padded(offset + 191, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_167, tvbrange, value) + tvbrange = padded(offset + 192, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_168, tvbrange, value) + tvbrange = padded(offset + 193, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_169, tvbrange, value) + tvbrange = padded(offset + 194, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_170, tvbrange, value) + tvbrange = padded(offset + 195, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_171, tvbrange, value) + tvbrange = padded(offset + 196, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_172, tvbrange, value) + tvbrange = padded(offset + 197, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_173, tvbrange, value) + tvbrange = padded(offset + 198, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_174, tvbrange, value) + tvbrange = padded(offset + 199, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_175, tvbrange, value) + tvbrange = padded(offset + 200, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_176, tvbrange, value) + tvbrange = padded(offset + 201, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_177, tvbrange, value) + tvbrange = padded(offset + 202, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_178, tvbrange, value) + tvbrange = padded(offset + 203, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_179, tvbrange, value) + tvbrange = padded(offset + 204, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_180, tvbrange, value) + tvbrange = padded(offset + 205, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_181, tvbrange, value) + tvbrange = padded(offset + 206, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_182, tvbrange, value) + tvbrange = padded(offset + 207, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_183, tvbrange, value) + tvbrange = padded(offset + 208, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_184, tvbrange, value) + tvbrange = padded(offset + 209, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_185, tvbrange, value) + tvbrange = padded(offset + 210, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_186, tvbrange, value) + tvbrange = padded(offset + 211, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_187, tvbrange, value) + tvbrange = padded(offset + 212, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_188, tvbrange, value) + tvbrange = padded(offset + 213, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_189, tvbrange, value) + tvbrange = padded(offset + 214, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_190, tvbrange, value) + tvbrange = padded(offset + 215, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_191, tvbrange, value) + tvbrange = padded(offset + 216, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_192, tvbrange, value) + tvbrange = padded(offset + 217, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_193, tvbrange, value) + tvbrange = padded(offset + 218, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_194, tvbrange, value) + tvbrange = padded(offset + 219, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_195, tvbrange, value) + tvbrange = padded(offset + 220, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_196, tvbrange, value) + tvbrange = padded(offset + 221, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_197, tvbrange, value) + tvbrange = padded(offset + 222, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_198, tvbrange, value) + tvbrange = padded(offset + 223, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_199, tvbrange, value) + tvbrange = padded(offset + 224, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_200, tvbrange, value) + tvbrange = padded(offset + 225, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_201, tvbrange, value) + tvbrange = padded(offset + 226, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_202, tvbrange, value) + tvbrange = padded(offset + 227, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_203, tvbrange, value) + tvbrange = padded(offset + 228, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_204, tvbrange, value) + tvbrange = padded(offset + 229, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_205, tvbrange, value) + tvbrange = padded(offset + 230, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_206, tvbrange, value) + tvbrange = padded(offset + 231, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_207, tvbrange, value) + tvbrange = padded(offset + 232, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_208, tvbrange, value) + tvbrange = padded(offset + 233, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_209, tvbrange, value) + tvbrange = padded(offset + 234, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_210, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_211, tvbrange, value) + tvbrange = padded(offset + 236, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_212, tvbrange, value) + tvbrange = padded(offset + 237, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_213, tvbrange, value) + tvbrange = padded(offset + 238, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_214, tvbrange, value) + tvbrange = padded(offset + 239, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_215, tvbrange, value) + tvbrange = padded(offset + 240, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_216, tvbrange, value) + tvbrange = padded(offset + 241, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_217, tvbrange, value) + tvbrange = padded(offset + 242, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_218, tvbrange, value) + tvbrange = padded(offset + 243, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_219, tvbrange, value) + tvbrange = padded(offset + 244, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_220, tvbrange, value) + tvbrange = padded(offset + 245, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_221, tvbrange, value) + tvbrange = padded(offset + 246, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_222, tvbrange, value) + tvbrange = padded(offset + 247, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_223, tvbrange, value) + tvbrange = padded(offset + 248, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_MESSAGE_PACK_messages_224, tvbrange, value) end -- dissect payload of message type OPEN_DRONE_ID_SYSTEM_UPDATE function payload_fns.payload_12919(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 18 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 18) @@ -40296,22 +51483,28 @@ function payload_fns.payload_12919(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 16 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_system, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_latitude, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_longitude, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_altitude_geo, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_timestamp, padded(field_offset, 4)) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_system, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_latitude, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_longitude, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_operator_altitude_geo, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.OPEN_DRONE_ID_SYSTEM_UPDATE_timestamp, tvbrange, value) end -- dissect payload of message type HYGROMETER_SENSOR function payload_fns.payload_12920(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 5 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 5) @@ -40319,16 +51512,19 @@ function payload_fns.payload_12920(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.HYGROMETER_SENSOR_id, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.HYGROMETER_SENSOR_temperature, padded(field_offset, 2)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.HYGROMETER_SENSOR_humidity, padded(field_offset, 2)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HYGROMETER_SENSOR_id, tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HYGROMETER_SENSOR_temperature, tvbrange, value) + tvbrange = padded(offset + 2, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HYGROMETER_SENSOR_humidity, tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_CFG function payload_fns.payload_10001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 20 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 20) @@ -40336,26 +51532,35 @@ function payload_fns.payload_10001(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_ICAO, padded(field_offset, 4)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_callsign, padded(field_offset, 9)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_emitterType, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_aircraftSize, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLat, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLon, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_stallSpeed, padded(field_offset, 2)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_rfSelect, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_ICAO, tvbrange, value) + tvbrange = padded(offset + 6, 9) + value = tvbrange:string() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_callsign, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_emitterType, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_aircraftSize, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLat, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_gpsOffsetLon, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_stallSpeed, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_rfSelect, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_OUT_RF_SELECT(subtree, "UAVIONIX_ADSB_OUT_CFG_rfSelect", tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_DYNAMIC function payload_fns.payload_10002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 41 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 41) @@ -40363,43 +51568,59 @@ function payload_fns.payload_10002(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_utcTime, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsLat, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsLon, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsAlt, padded(field_offset, 4)) - field_offset = offset + 38 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsFix, padded(field_offset, 1)) - field_offset = offset + 39 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_numSats, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_baroAltMSL, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_accuracyHor, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_accuracyVert, padded(field_offset, 2)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_accuracyVel, padded(field_offset, 2)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_velVert, padded(field_offset, 2)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_velNS, padded(field_offset, 2)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_VelEW, padded(field_offset, 2)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_emergencyStatus, padded(field_offset, 1)) - field_offset = offset + 34 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_state, padded(field_offset, 2)) - dissect_flags_UAVIONIX_ADSB_OUT_DYNAMIC_STATE(subtree, "UAVIONIX_ADSB_OUT_DYNAMIC_state", value) - field_offset = offset + 36 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_squawk, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_utcTime, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsLat, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsLon, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsAlt, tvbrange, value) + tvbrange = padded(offset + 38, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_gpsFix, tvbrange, value) + tvbrange = padded(offset + 39, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_numSats, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_baroAltMSL, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_accuracyHor, tvbrange, value) + tvbrange = padded(offset + 24, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_accuracyVert, tvbrange, value) + tvbrange = padded(offset + 26, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_accuracyVel, tvbrange, value) + tvbrange = padded(offset + 28, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_velVert, tvbrange, value) + tvbrange = padded(offset + 30, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_velNS, tvbrange, value) + tvbrange = padded(offset + 32, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_VelEW, tvbrange, value) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_emergencyStatus, tvbrange, value) + tvbrange = padded(offset + 34, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_state, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_OUT_DYNAMIC_STATE(subtree, "UAVIONIX_ADSB_OUT_DYNAMIC_state", tvbrange, value) + tvbrange = padded(offset + 36, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_DYNAMIC_squawk, tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT function payload_fns.payload_10003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 1 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 1) @@ -40407,12 +51628,14 @@ function payload_fns.payload_10003(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_RF_HEALTH(subtree, "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_rfHealth", tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_CFG_REGISTRATION function payload_fns.payload_10004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -40420,12 +51643,13 @@ function payload_fns.payload_10004(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_REGISTRATION_registration, padded(field_offset, 9)) + tvbrange = padded(offset + 0, 9) + value = tvbrange:string() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_REGISTRATION_registration, tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_CFG_FLIGHTID function payload_fns.payload_10005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -40433,12 +51657,13 @@ function payload_fns.payload_10005(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_FLIGHTID_flight_id, padded(field_offset, 9)) + tvbrange = padded(offset + 0, 9) + value = tvbrange:string() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CFG_FLIGHTID_flight_id, tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_GET function payload_fns.payload_10006(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 4 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 4) @@ -40446,12 +51671,13 @@ function payload_fns.payload_10006(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_GET_ReqMessageId, padded(field_offset, 4)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_GET_ReqMessageId, tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_CONTROL function payload_fns.payload_10007(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 17 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 17) @@ -40459,23 +51685,30 @@ function payload_fns.payload_10007(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 6 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_state, padded(field_offset, 1)) - dissect_flags_UAVIONIX_ADSB_OUT_CONTROL_STATE(subtree, "UAVIONIX_ADSB_OUT_CONTROL_state", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_baroAltMSL, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_squawk, padded(field_offset, 2)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_emergencyStatus, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_flight_id, padded(field_offset, 8)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_x_bit, padded(field_offset, 1)) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_state, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_OUT_CONTROL_STATE(subtree, "UAVIONIX_ADSB_OUT_CONTROL_state", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_baroAltMSL, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_squawk, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_emergencyStatus, tvbrange, value) + tvbrange = padded(offset + 8, 8) + value = tvbrange:string() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_flight_id, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_CONTROL_x_bit, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_XBIT(subtree, "UAVIONIX_ADSB_OUT_CONTROL_x_bit", tvbrange, value) end -- dissect payload of message type UAVIONIX_ADSB_OUT_STATUS function payload_fns.payload_10008(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 14 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 14) @@ -40483,24 +51716,30 @@ function payload_fns.payload_10008(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 2 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_state, padded(field_offset, 1)) - dissect_flags_UAVIONIX_ADSB_OUT_STATUS_STATE(subtree, "UAVIONIX_ADSB_OUT_STATUS_state", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_squawk, padded(field_offset, 2)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_NIC_NACp, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_boardTemp, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_fault, padded(field_offset, 1)) - dissect_flags_UAVIONIX_ADSB_OUT_STATUS_FAULT(subtree, "UAVIONIX_ADSB_OUT_STATUS_fault", value) - field_offset = offset + 6 - subtree, value = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_flight_id, padded(field_offset, 8)) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_state, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_OUT_STATUS_STATE(subtree, "UAVIONIX_ADSB_OUT_STATUS_state", tvbrange, value) + tvbrange = padded(offset + 0, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_squawk, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_NIC_NACp, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_boardTemp, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_fault, tvbrange, value) + dissect_flags_UAVIONIX_ADSB_OUT_STATUS_FAULT(subtree, "UAVIONIX_ADSB_OUT_STATUS_fault", tvbrange, value) + tvbrange = padded(offset + 6, 8) + value = tvbrange:string() + subtree = tree:add_le(f.UAVIONIX_ADSB_OUT_STATUS_flight_id, tvbrange, value) end -- dissect payload of message type ICAROUS_HEARTBEAT function payload_fns.payload_42000(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 1 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 1) @@ -40508,12 +51747,13 @@ function payload_fns.payload_42000(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.ICAROUS_HEARTBEAT_status, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ICAROUS_HEARTBEAT_status, tvbrange, value) end -- dissect payload of message type ICAROUS_KINEMATIC_BANDS function payload_fns.payload_42001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 46 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 46) @@ -40521,42 +51761,58 @@ function payload_fns.payload_42001(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 40 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_numBands, padded(field_offset, 1)) - field_offset = offset + 41 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type1, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min1, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max1, padded(field_offset, 4)) - field_offset = offset + 42 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type2, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min2, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max2, padded(field_offset, 4)) - field_offset = offset + 43 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type3, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min3, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max3, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type4, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min4, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max4, padded(field_offset, 4)) - field_offset = offset + 45 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type5, padded(field_offset, 1)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min5, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max5, padded(field_offset, 4)) + tvbrange = padded(offset + 40, 1) + value = tvbrange:le_int() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_numBands, tvbrange, value) + tvbrange = padded(offset + 41, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type1, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min1, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max1, tvbrange, value) + tvbrange = padded(offset + 42, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type2, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min2, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max2, tvbrange, value) + tvbrange = padded(offset + 43, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type3, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min3, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max3, tvbrange, value) + tvbrange = padded(offset + 44, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type4, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min4, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max4, tvbrange, value) + tvbrange = padded(offset + 45, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_type5, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_min5, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.ICAROUS_KINEMATIC_BANDS_max5, tvbrange, value) end -- dissect payload of message type LOWEHEISER_GOV_EFI function payload_fns.payload_10151(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 85 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 85) @@ -40564,56 +51820,79 @@ function payload_fns.payload_10151(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_volt_batt, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_curr_batt, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_curr_gen, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_curr_rot, padded(field_offset, 4)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_fuel_level, padded(field_offset, 4)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_throttle, padded(field_offset, 4)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_runtime, padded(field_offset, 4)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_until_maintenance, padded(field_offset, 4)) - field_offset = offset + 32 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_rectifier_temp, padded(field_offset, 4)) - field_offset = offset + 36 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_generator_temp, padded(field_offset, 4)) - field_offset = offset + 40 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_batt, padded(field_offset, 4)) - field_offset = offset + 44 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_rpm, padded(field_offset, 4)) - field_offset = offset + 48 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_pw, padded(field_offset, 4)) - field_offset = offset + 52 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_fuel_flow, padded(field_offset, 4)) - field_offset = offset + 56 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_fuel_consumed, padded(field_offset, 4)) - field_offset = offset + 60 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_baro, padded(field_offset, 4)) - field_offset = offset + 64 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_mat, padded(field_offset, 4)) - field_offset = offset + 68 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_clt, padded(field_offset, 4)) - field_offset = offset + 72 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_tps, padded(field_offset, 4)) - field_offset = offset + 76 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_exhaust_gas_temperature, padded(field_offset, 4)) - field_offset = offset + 84 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_index, padded(field_offset, 1)) - field_offset = offset + 80 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_generator_status, padded(field_offset, 2)) - field_offset = offset + 82 - subtree, value = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_status, padded(field_offset, 2)) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_volt_batt, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_curr_batt, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_curr_gen, tvbrange, value) + tvbrange = padded(offset + 12, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_curr_rot, tvbrange, value) + tvbrange = padded(offset + 16, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_fuel_level, tvbrange, value) + tvbrange = padded(offset + 20, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_throttle, tvbrange, value) + tvbrange = padded(offset + 24, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_runtime, tvbrange, value) + tvbrange = padded(offset + 28, 4) + value = tvbrange:le_int() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_until_maintenance, tvbrange, value) + tvbrange = padded(offset + 32, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_rectifier_temp, tvbrange, value) + tvbrange = padded(offset + 36, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_generator_temp, tvbrange, value) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_batt, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_rpm, tvbrange, value) + tvbrange = padded(offset + 48, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_pw, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_fuel_flow, tvbrange, value) + tvbrange = padded(offset + 56, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_fuel_consumed, tvbrange, value) + tvbrange = padded(offset + 60, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_baro, tvbrange, value) + tvbrange = padded(offset + 64, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_mat, tvbrange, value) + tvbrange = padded(offset + 68, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_clt, tvbrange, value) + tvbrange = padded(offset + 72, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_tps, tvbrange, value) + tvbrange = padded(offset + 76, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_exhaust_gas_temperature, tvbrange, value) + tvbrange = padded(offset + 84, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_index, tvbrange, value) + tvbrange = padded(offset + 80, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_generator_status, tvbrange, value) + tvbrange = padded(offset + 82, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.LOWEHEISER_GOV_EFI_efi_status, tvbrange, value) end -- dissect payload of message type CUBEPILOT_RAW_RC function payload_fns.payload_50001(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 32 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 32) @@ -40621,74 +51900,106 @@ function payload_fns.payload_50001(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 0 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_0, padded(field_offset, 1)) - field_offset = offset + 1 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_1, padded(field_offset, 1)) - field_offset = offset + 2 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_2, padded(field_offset, 1)) - field_offset = offset + 3 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_3, padded(field_offset, 1)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_4, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_5, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_6, padded(field_offset, 1)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_7, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_8, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_9, padded(field_offset, 1)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_10, padded(field_offset, 1)) - field_offset = offset + 11 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_11, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_12, padded(field_offset, 1)) - field_offset = offset + 13 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_13, padded(field_offset, 1)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_14, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_15, padded(field_offset, 1)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_16, padded(field_offset, 1)) - field_offset = offset + 17 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_17, padded(field_offset, 1)) - field_offset = offset + 18 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_18, padded(field_offset, 1)) - field_offset = offset + 19 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_19, padded(field_offset, 1)) - field_offset = offset + 20 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_20, padded(field_offset, 1)) - field_offset = offset + 21 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_21, padded(field_offset, 1)) - field_offset = offset + 22 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_22, padded(field_offset, 1)) - field_offset = offset + 23 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_23, padded(field_offset, 1)) - field_offset = offset + 24 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_24, padded(field_offset, 1)) - field_offset = offset + 25 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_25, padded(field_offset, 1)) - field_offset = offset + 26 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_26, padded(field_offset, 1)) - field_offset = offset + 27 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_27, padded(field_offset, 1)) - field_offset = offset + 28 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_28, padded(field_offset, 1)) - field_offset = offset + 29 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_29, padded(field_offset, 1)) - field_offset = offset + 30 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_30, padded(field_offset, 1)) - field_offset = offset + 31 - subtree, value = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_31, padded(field_offset, 1)) + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_0, tvbrange, value) + tvbrange = padded(offset + 1, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_1, tvbrange, value) + tvbrange = padded(offset + 2, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_2, tvbrange, value) + tvbrange = padded(offset + 3, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_3, tvbrange, value) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_4, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_5, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_6, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_7, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_8, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_9, tvbrange, value) + tvbrange = padded(offset + 10, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_10, tvbrange, value) + tvbrange = padded(offset + 11, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_11, tvbrange, value) + tvbrange = padded(offset + 12, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_12, tvbrange, value) + tvbrange = padded(offset + 13, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_13, tvbrange, value) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_14, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_15, tvbrange, value) + tvbrange = padded(offset + 16, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_16, tvbrange, value) + tvbrange = padded(offset + 17, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_17, tvbrange, value) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_18, tvbrange, value) + tvbrange = padded(offset + 19, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_19, tvbrange, value) + tvbrange = padded(offset + 20, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_20, tvbrange, value) + tvbrange = padded(offset + 21, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_21, tvbrange, value) + tvbrange = padded(offset + 22, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_22, tvbrange, value) + tvbrange = padded(offset + 23, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_23, tvbrange, value) + tvbrange = padded(offset + 24, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_24, tvbrange, value) + tvbrange = padded(offset + 25, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_25, tvbrange, value) + tvbrange = padded(offset + 26, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_26, tvbrange, value) + tvbrange = padded(offset + 27, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_27, tvbrange, value) + tvbrange = padded(offset + 28, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_28, tvbrange, value) + tvbrange = padded(offset + 29, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_29, tvbrange, value) + tvbrange = padded(offset + 30, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_30, tvbrange, value) + tvbrange = padded(offset + 31, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_RAW_RC_rc_raw_31, tvbrange, value) end -- dissect payload of message type HERELINK_VIDEO_STREAM_INFORMATION function payload_fns.payload_50002(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 246 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 246) @@ -40696,26 +52007,34 @@ function payload_fns.payload_50002(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 14 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_camera_id, padded(field_offset, 1)) - field_offset = offset + 15 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_status, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_framerate, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_resolution_h, padded(field_offset, 2)) - field_offset = offset + 10 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_resolution_v, padded(field_offset, 2)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_bitrate, padded(field_offset, 4)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_rotation, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_uri, padded(field_offset, 230)) + tvbrange = padded(offset + 14, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_camera_id, tvbrange, value) + tvbrange = padded(offset + 15, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_status, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_framerate, tvbrange, value) + tvbrange = padded(offset + 8, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_resolution_h, tvbrange, value) + tvbrange = padded(offset + 10, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_resolution_v, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_bitrate, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_rotation, tvbrange, value) + tvbrange = padded(offset + 16, 230) + value = tvbrange:string() + subtree = tree:add_le(f.HERELINK_VIDEO_STREAM_INFORMATION_uri, tvbrange, value) end -- dissect payload of message type HERELINK_TELEM function payload_fns.payload_50003(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 19 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 19) @@ -40723,24 +52042,31 @@ function payload_fns.payload_50003(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 18 - subtree, value = tree:add_le(f.HERELINK_TELEM_rssi, padded(field_offset, 1)) - field_offset = offset + 12 - subtree, value = tree:add_le(f.HERELINK_TELEM_snr, padded(field_offset, 2)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.HERELINK_TELEM_rf_freq, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.HERELINK_TELEM_link_bw, padded(field_offset, 4)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HERELINK_TELEM_link_rate, padded(field_offset, 4)) - field_offset = offset + 14 - subtree, value = tree:add_le(f.HERELINK_TELEM_cpu_temp, padded(field_offset, 2)) - field_offset = offset + 16 - subtree, value = tree:add_le(f.HERELINK_TELEM_board_temp, padded(field_offset, 2)) + tvbrange = padded(offset + 18, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_TELEM_rssi, tvbrange, value) + tvbrange = padded(offset + 12, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HERELINK_TELEM_snr, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_TELEM_rf_freq, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_TELEM_link_bw, tvbrange, value) + tvbrange = padded(offset + 8, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HERELINK_TELEM_link_rate, tvbrange, value) + tvbrange = padded(offset + 14, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HERELINK_TELEM_cpu_temp, tvbrange, value) + tvbrange = padded(offset + 16, 2) + value = tvbrange:le_int() + subtree = tree:add_le(f.HERELINK_TELEM_board_temp, tvbrange, value) end -- dissect payload of message type CUBEPILOT_FIRMWARE_UPDATE_START function payload_fns.payload_50004(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 10 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 10) @@ -40748,18 +52074,22 @@ function payload_fns.payload_50004(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 8 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_target_system, padded(field_offset, 1)) - field_offset = offset + 9 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_size, padded(field_offset, 4)) - field_offset = offset + 4 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_crc, padded(field_offset, 4)) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_target_system, tvbrange, value) + tvbrange = padded(offset + 9, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_size, tvbrange, value) + tvbrange = padded(offset + 4, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_START_crc, tvbrange, value) end -- dissect payload of message type CUBEPILOT_FIRMWARE_UPDATE_RESP function payload_fns.payload_50005(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 6 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 6) @@ -40767,16 +52097,19 @@ function payload_fns.payload_50005(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_system, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_component, padded(field_offset, 1)) - field_offset = offset + 0 - subtree, value = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset, padded(field_offset, 4)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_system, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_component, tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset, tvbrange, value) end -- dissect payload of message type HEARTBEAT function payload_fns.payload_0(buffer, tree, msgid, offset, limit, pinfo) - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + 9 > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + 9) @@ -40784,19 +52117,25 @@ function payload_fns.payload_0(buffer, tree, msgid, offset, limit, pinfo) else padded = buffer end - field_offset = offset + 4 - subtree, value = tree:add_le(f.HEARTBEAT_type, padded(field_offset, 1)) - field_offset = offset + 5 - subtree, value = tree:add_le(f.HEARTBEAT_autopilot, padded(field_offset, 1)) - field_offset = offset + 6 - subtree, value = tree:add_le(f.HEARTBEAT_base_mode, padded(field_offset, 1)) - dissect_flags_MAV_MODE_FLAG(subtree, "HEARTBEAT_base_mode", value) - field_offset = offset + 0 - subtree, value = tree:add_le(f.HEARTBEAT_custom_mode, padded(field_offset, 4)) - field_offset = offset + 7 - subtree, value = tree:add_le(f.HEARTBEAT_system_status, padded(field_offset, 1)) - field_offset = offset + 8 - subtree, value = tree:add_le(f.HEARTBEAT_mavlink_version, padded(field_offset, 1)) + tvbrange = padded(offset + 4, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HEARTBEAT_type, tvbrange, value) + tvbrange = padded(offset + 5, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HEARTBEAT_autopilot, tvbrange, value) + tvbrange = padded(offset + 6, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HEARTBEAT_base_mode, tvbrange, value) + dissect_flags_MAV_MODE_FLAG(subtree, "HEARTBEAT_base_mode", tvbrange, value) + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HEARTBEAT_custom_mode, tvbrange, value) + tvbrange = padded(offset + 7, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HEARTBEAT_system_status, tvbrange, value) + tvbrange = padded(offset + 8, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.HEARTBEAT_mavlink_version, tvbrange, value) end -- dissector function function mavlink_proto.dissector(buffer,pinfo,tree) @@ -41008,8 +52347,14 @@ end wtap_encap = DissectorTable.get("wtap_encap") wtap_encap:add(wtap.USER0, mavlink_proto) --- bind protocol dissector to port 14550 and 14580 +-- bind protocol dissector to ports: 14550, 14580, 18570 local udp_dissector_table = DissectorTable.get("udp.port") udp_dissector_table:add(14550, mavlink_proto) udp_dissector_table:add(14580, mavlink_proto) +udp_dissector_table:add(18570, mavlink_proto) + +-- register common Mavlink TCP ports + +DissectorTable.get("tcp.port"):add("5760-5763", mavlink_proto) + diff --git a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml index 5947992560..d059979191 100644 --- a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml +++ b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml @@ -333,6 +333,16 @@ Empty Empty + + Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link. + Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy. + The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known. + estimated one standard deviation accuracy of the measurement. Set to NaN if not known. + Empty + Latitude + Longitude + Altitude, not used. Should be sent as NaN. May be supported in a future version of this message. + diff --git a/ExtLibs/Mavlink/message_definitions/common.xml b/ExtLibs/Mavlink/message_definitions/common.xml index 9374561451..84b29c5202 100644 --- a/ExtLibs/Mavlink/message_definitions/common.xml +++ b/ExtLibs/Mavlink/message_definitions/common.xml @@ -438,6 +438,57 @@ Gimbal device supports yawing/panning infinetely (e.g. using slip disk). + + Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags. + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME. + + + Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS. + + + Gimbal manager supports to point to a local position. + + + Gimbal manager supports to point to a global latitude, longitude, altitude position. + + Flags for gimbal device (lower level) operation. @@ -595,6 +646,36 @@ Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored. + + Flags to indicate the type of storage. + + Storage type is not known. + + + Storage type is USB device. + + + Storage type is SD card. + + + Storage type is microSD card. + + + Storage type is CFast. + + + Storage type is CFexpress. + + + Storage type is XQD. + + + Storage type is HD mass storage type. + + + Storage type is other, not listed type. + + Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE. @@ -1541,6 +1622,16 @@ Gimbal manager flags to use. Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + + + + Gimbal configuration to set which sysid/compid is in primary and secondary control. + Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). + Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). + Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). + Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). + Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. Reserved (Set to 0) @@ -2037,36 +2128,6 @@ Point toward of given id. - - ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. - - Command / mission item is ok. - - - Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. - - - The system is refusing to accept this command from this source / communication partner. - - - Command or mission item is not supported, other commands would be accepted. - - - The coordinate frame of this command / mission item is not supported. - - - The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. - - - The X or latitude value is out of range. - - - The Y or longitude value is out of range. - - - The Z or altitude value is out of range. - - Specifies the datatype of a MAVLink parameter. @@ -3949,6 +4010,31 @@ Use a fixed wing approach before detransitioning and landing vertically. + + + States of the mission state machine. + Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). + They may not all be relevant on all vehicles. + + + The mission status reporting is not supported. + + + No mission on the vehicle. + + + Mission has not started. This is the case after a mission has uploaded but not yet started executing. + + + Mission is active, and will execute mission items when in auto mode. + + + Mission is paused when in auto mode. + + + Mission has executed all mission items. + + @@ -4267,6 +4353,10 @@ Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. Sequence + + Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. + Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. + Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). Request the overall list of mission items from the system/component. @@ -5268,7 +5358,7 @@ Firmware version number Middleware version number Operating system version number - HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt + HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/ardupilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. @@ -5621,24 +5711,24 @@ Timestamp (time since system boot). Name of the camera vendor Name of the camera model - Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff) - Focal length - Image sensor size horizontal - Image sensor size vertical - Horizontal image resolution - Vertical image resolution - Reserved for a lens ID + Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. + Focal length. Use NaN if not known. + Image sensor size horizontal. Use NaN if not known. + Image sensor size vertical. Use NaN if not known. + Horizontal image resolution. Use 0 if not known. + Vertical image resolution. Use 0 if not known. + Reserved for a lens ID. Use 0 if not known. Bitmap of camera capability flags. - Camera definition version (iteration) - Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). + Camera definition version (iteration). Use 0 if not known. + Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. Timestamp (time since system boot). Camera mode - Current zoom level (0.0 to 100.0, NaN if not known) - Current focus level (0.0 to 100.0, NaN if not known) + Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) + Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc. @@ -5788,6 +5878,32 @@ Heading in radians, in NED. NAN if unknown Accuracy of heading, in NED. NAN if unknown + + + + Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. + Timestamp (time since system boot). + Bitmap of gimbal capability flags. + Gimbal device ID that this gimbal manager is responsible for. + Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) + Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) + Minimum pitch angle (positive: up, negative: down) + Maximum pitch angle (positive: up, negative: down) + Minimum yaw angle (positive: to the right, negative: to the left) + Maximum yaw angle (positive: to the right, negative: to the left) + + + + + Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz). + Timestamp (time since system boot). + High level gimbal manager flags currently applied. + Gimbal device ID that this gimbal manager is responsible for. + System ID of MAVLink component with primary control, 0 for none. + Component ID of MAVLink component with primary control, 0 for none. + System ID of MAVLink component with secondary control, 0 for none. + Component ID of MAVLink component with secondary control, 0 for none. + Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.. Timestamp (time since system boot). @@ -5860,6 +5976,19 @@ Y component of angular velocity, positive is pitching up, NaN to be ignored. Z component of angular velocity, positive is yawing to the right, NaN to be ignored. + + + + High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. + System ID + Component ID + High level gimbal manager flags to use. + Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). + Pitch angle (positive: up, negative: down, NaN to be ignored). + Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). + Pitch angular rate (positive: up, negative: down, NaN to be ignored). + Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). + Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. @@ -5976,6 +6105,7 @@ Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. Type of estimator that is providing the odometry. + Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality Status of the Iridium SBD link. diff --git a/ExtLibs/Mavlink/pymavlink/generator/mavgen_wlua.py b/ExtLibs/Mavlink/pymavlink/generator/mavgen_wlua.py index d7a4a771f1..8cec0d5bae 100644 --- a/ExtLibs/Mavlink/pymavlink/generator/mavgen_wlua.py +++ b/ExtLibs/Mavlink/pymavlink/generator/mavgen_wlua.py @@ -1,45 +1,34 @@ -#!/usr/bin/env python ''' -parse a MAVLink protocol XML file and generate a Wireshark LUA dissector +parse a MAVLink protocol XML file and generate a Wireshark Lua dissector + +Example usage on Linux or macOS: + +# assuming you have cloned the mavlink repo to /mavlink +MXML="/mavlink/message_definitions/v1.0/ardupilotmega.xml" +# Wireshark -> About Wireshark -> Folders -> Personal Lua Plugins +WIRESHARK_PLUGINS="~/.local/lib/wireshark/plugins" +mkdir -p $WIRESHARK_PLUGINS +mavgen.py --lang=WLua $MXML -o $WIRESHARK_PLUGINS/mavlink.lua + +After doing this, Wireshark should be able to show details of MAVLink packets. + +--- Copyright Holger Steinhaus 2012 Released under GNU GPL version 3 or later - -Instructions for use: -1. python -m pymavlink.tools.mavgen --lang=WLua mymavlink.xml -o ~/.wireshark/plugins/mymavlink.lua -2. convert binary stream int .pcap file format (see ../examples/mav2pcap.py) -3. open the pcap file in Wireshark ''' from __future__ import print_function from builtins import range import os -import re from . import mavparse, mavtemplate t = mavtemplate.MAVTemplate() - -def type_size(mavlink_type): - # infer size of mavlink types - re_int = re.compile('^(u?)int(8|16|32|64)_t$') - int_parts = re_int.findall(mavlink_type) - if len(int_parts): - return (int(int_parts[0][1]) // 8) - elif mavlink_type == 'float': - return 4 - elif mavlink_type == 'double': - return 8 - elif mavlink_type == 'char': - return 1 - else: - raise Exception('unsupported MAVLink type - please fix me') - - def get_field_info(field): mavlink_type = field.type - size = type_size(mavlink_type) + size = field.type_length count = field.array_length if field.array_length > 0 else 1 if mavlink_type == "char": @@ -52,10 +41,6 @@ def get_field_info(field): # (u)int types field_type = "ftypes." + mavlink_type.replace("_t", "").upper() tvb_func = "le_" + ("u" if "u" in mavlink_type else "") + "int" + ("64" if "64" in mavlink_type else "") - elif field.enum: - # enum types in float/double fields (these will come up at least with command params) - field_type = "ftypes.UINT32" - tvb_func = "le_" + mavlink_type else: # float/double field_type = "ftypes." + mavlink_type.upper() @@ -71,7 +56,6 @@ def generate_preamble(outf): -- Wireshark dissector for the MAVLink protocol (please see https://mavlink.io/en for details) unknownFrameBeginOffset = 0 -local bit = require "bit32" mavlink_proto = Proto("mavlink_proto", "MAVLink protocol") f = mavlink_proto.fields @@ -111,7 +95,6 @@ def generate_body_fields(outf): f.signature_signature = ProtoField.bytes("mavlink_proto.signature_signature", "Signature") f.rawheader = ProtoField.bytes("mavlink_proto.rawheader", "Unparsable header fragment") f.rawpayload = ProtoField.bytes("mavlink_proto.rawpayload", "Unparsable payload") - """) @@ -131,40 +114,17 @@ def generate_msg_table(outf, msgs): """) -def is_power_of_2(number): - if number <= 0: - return False - while number: - if (number & 1) and number != 1: - return False - number >>= 1 - return True - - -def log2_power_of_2(number): - log = -1 - while number: - number >>= 1 - log += 1 - return log +def is_power_of_2(n): + assert isinstance(n, int) + return (n & (n-1) == 0) and n != 0 def generate_enum_table(outf, enums): - for enum in enums: - assert isinstance(enum, mavparse.MAVEnum) - - # Heuristic for detecting flags fields. - # Assume an enum is a flag field if it consists of only zero, powers of two, - # and the autogenerated 'xxx_ENUM_END'. - # Additionally require either >= 3 powers of two or 'FLAG' in the enum name - # (play safe and don't assume 0,1,2 are flags, but 0,1,2,4 likely are). - enum.is_flags = all(is_power_of_2(entry.value) or entry.name.endswith("_ENUM_END") for entry in enum.entry) \ - and ("FLAG" in enum.name.upper() or sum(is_power_of_2(entry.value) for entry in enum.entry) >= 3) - t.write(outf, """ -enumEntryName = { +local enumEntryName = { """) for enum in enums: + assert isinstance(enum, mavparse.MAVEnum) t.write(outf, """ ["${enumname}"] = { """, {'enumname': enum.name}) @@ -184,37 +144,41 @@ def generate_enum_table(outf, enums): """) -def generate_field_or_param(outf, field_or_param, name, label, display_type, field_type, enums): - values = flags = "nil" - field_or_param.flag_enum = None +def generate_field_or_param(outf, field_or_param, name, label, physical_type, field_type, enums): + assert isinstance(field_or_param, mavparse.MAVEnumParam) or isinstance(field_or_param, mavparse.MAVField) + values = "nil" + enum_obj = None + if field_or_param.enum: + enum_obj = next((enum for enum in enums if enum.name == field_or_param.enum), None) if field_or_param.enum: # display name of enum instead of base type display_type = field_or_param.enum - # send enum object along for flags enums - enum_obj = next((enum for enum in enums if enum.name == field_or_param.enum), None) - if enum_obj and enum_obj.is_flags: - field_or_param.flag_enum = enum_obj # show enum values for non-flags enums - else: + if not enum_obj.bitmask: values = "enumEntryName." + field_or_param.enum # force display type of enums to uint32 so we can show the names if field_type in ("ftypes.FLOAT", "ftypes.DOUBLE"): field_type = "ftypes.UINT32" - + else: + display_type = physical_type t.write(outf, """ f.${fname} = ProtoField.new("${flabel} (${ftypename})", "mavlink_proto.${fname}", ${ftype}, ${fvalues}) """, {'fname': name, 'flabel': label, 'ftypename': display_type, 'ftype': field_type, 'fvalues': values}) # generate flag enum subfields - if field_or_param.flag_enum: - for entry in field_or_param.flag_enum.entry: - if is_power_of_2(entry.value): - t.write(outf, + if enum_obj and enum_obj.bitmask: + physical_bits = max(entry.value.bit_length() for entry in enum_obj.entry) + for entry in enum_obj.entry: + if not is_power_of_2(entry.value): + # omit flag enums have values like "0: None" + continue + + t.write(outf, """ -f.${fname}_flag${ename} = ProtoField.bool("mavlink_proto.${fname}.${ename}", "${ename}") -""", {'fname': name, 'ename': entry.name}) +f.${fname}_flag${ename} = ProtoField.bool("mavlink_proto.${fname}.${ename}", "${ename}", ${fbits}, nil, ${evalue}) +""", {'fname': name, 'ename': entry.name, 'fbits': physical_bits, 'evalue': entry.value}) def generate_msg_fields(outf, msg, enums): @@ -257,32 +221,16 @@ def generate_flag_enum_dissector(outf, enum): t.write(outf, """ -- dissect flag field -function dissect_flags_${enumname}(tree, name, value) - local bitval +function dissect_flags_${enumname}(tree, name, tvbrange, value) """, {'enumname': enum.name}) - # find number of bits in enum real_entries = [entry for entry in enum.entry if is_power_of_2(entry.value)] - bits = 0 - while any(entry.value > (1 << bits) for entry in real_entries): - bits += 1 - bits += 1 - # round up to 8 bits - bits += -bits % 8 - - template = "".join(". " if i % 4 == 3 else "." for i in range(bits)) for entry in real_entries: - bit = log2_power_of_2(entry.value) - # position in template - split = bits - bit - 1 - # accommodate for spaces - split += split // 4 t.write(outf, """ - bitval = bit.band(bit.rshift(value, ${bitno}), 1) - tree:add(f[name .. "_flag${entryname}"], bitval ~= 0, "${tleft}" .. tostring(bitval) .. "${tright}${entryname}: " .. tostring(bitval ~= 0)) -""", {'bitno': bit, 'entryname': entry.name, 'tleft': template[:split], 'tright': template[split + 1:]}) + tree:add_le(f[name .. "_flag${entryname}"], tvbrange, value) +""", {'entryname': entry.name}) t.write(outf, """ @@ -290,17 +238,22 @@ def generate_flag_enum_dissector(outf, enum): """) -def generate_field_dissector(outf, msg, field, offset, cmd=None, param=None): +def generate_field_dissector(outf, msg, field, offset, enums, cmd=None, param=None): + # field is the PHYSICAL type + # but param may have a different LOGICAL type assert isinstance(field, mavparse.MAVField) - + assert cmd is None or isinstance(cmd, mavparse.MAVEnumEntry) + assert param is None or isinstance(param, mavparse.MAVEnumParam) + _, _, tvb_func, size, count = get_field_info(field) - flag_enum = param.flag_enum if param else field.flag_enum - + 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) + # handle arrays, but not strings - + for i in range(0,count): - if count>1: + if count>1: index_text = '_' + str(i) else: index_text = '' @@ -312,33 +265,27 @@ def generate_field_dissector(outf, msg, field, offset, cmd=None, param=None): t.write(outf, """ - field_offset = offset + ${foffset} - subtree, value = tree:add_le(f.${fvar}, padded(field_offset, ${fbytes})) + tvbrange = padded(offset + ${foffset}, ${fbytes}) + value = tvbrange:${ftvbfunc}() + subtree = tree:add_le(f.${fvar}, tvbrange, value) """, {'foffset': offset + i * size, 'fbytes': size, 'ftvbfunc': tvb_func, 'fvar': field_var}) - if flag_enum is not None: + if enum_obj and enum_obj.bitmask: t.write(outf, """ - dissect_flags_${enumname}(subtree, "${fvar}", value) -""", {'enumname': flag_enum.name, 'fvar': field_var}) + dissect_flags_${enumname}(subtree, "${fvar}", tvbrange, value) +""", {'enumname': enum_name, 'fvar': field_var}) -def generate_payload_dissector(outf, msg, cmds, cmd=None): - total_size = 0 - offsets = {} - for f in msg.ordered_fields: - _, _, _, size, count = get_field_info(f) - offsets[f.name] = total_size - total_size += size * count - +def generate_payload_dissector(outf, msg, cmds, enums, cmd=None): # detect command messages (but not in already command-specific dissectors) - has_commands = cmds and msg.name in ("COMMAND_INT", "COMMAND_LONG", "COMMAND_ACK", "COMMAND_CANCEL") and "command" in offsets + has_commands = cmds and msg.name in ("COMMAND_INT", "COMMAND_LONG", "COMMAND_ACK", "COMMAND_CANCEL") and "command" in msg.field_offsets has_args = has_commands and msg.name in ("COMMAND_INT", "COMMAND_LONG") # for command messages with args, generate command-specific dissectors if has_args: for subcmd in cmds: - generate_payload_dissector(outf, msg, None, subcmd) + generate_payload_dissector(outf, msg, None,enums, cmd=subcmd) # function header if cmd is not None: @@ -357,7 +304,7 @@ def generate_payload_dissector(outf, msg, cmds, cmd=None): # validate and pad payload if necessary t.write(outf, """ - local padded, field_offset, value, subtree + local padded, field_offset, value, subtree, tvbrange if (offset + ${msgbytes} > limit) then padded = buffer(0, limit):bytes() padded:set_size(offset + ${msgbytes}) @@ -365,7 +312,7 @@ def generate_payload_dissector(outf, msg, cmds, cmd=None): else padded = buffer end -""", {'msgbytes': total_size}) +""", {'msgbytes': msg.wire_length}) # for all command messages, show the command name in the info field if has_commands: @@ -376,7 +323,7 @@ def generate_payload_dissector(outf, msg, cmds, cmd=None): if cmd_name ~= nil then pinfo.cols.info:append(": " .. cmd_name) end -""", {'foffset': offsets["command"]}) +""", {'foffset': msg.field_offsets['command']}) # for command messages with args, call command-specific dissector if known if has_args: @@ -393,17 +340,16 @@ def generate_payload_dissector(outf, msg, cmds, cmd=None): # detect command params param = None if cmd is not None: - param_index = None - # most params of COMMAND_INT and COMMAND_LONG - if field.name.startswith("param") and field.name[5:].isdigit(): - param_index = int(field.name[5:]) - # xyz params of COMMAND_INT - elif msg.name == "COMMAND_INT" and field.name in ("x", "y", "z"): - param_index = ("x", "y", "z").index(field.name) + 5 + param_index = {'param1': 1, 'param2': 2, 'param3': 3, 'param4': 4, 'param5': 5, 'param6': 6, 'param7': 7, 'x': 5, 'y': 6, 'z': 7}.get(field.name) - param = param_index and next((p for p in cmd.param if int(p.index) == param_index and p.label), None) + for p in cmd.param: + if int(p.index) == param_index: + param = p + break + if param_index is not None: + param = next((p for p in cmd.param if int(p.index) == param_index and p.label), None) - generate_field_dissector(outf, msg, field, offsets[field.name], cmd, param) + generate_field_dissector(outf, msg, field, msg.field_offsets[field.name], enums, cmd, param) t.write(outf, """ @@ -510,9 +456,9 @@ def generate_packet_dis(outf): offset = offset + 1 else -- handle truncated header - local hsize = buffer:len() - 2 - offset - subtree:add(f.rawheader, buffer(offset, hsize)) - offset = offset + hsize + pinfo.desegment_len = DESEGMENT_ONE_MORE_SEGMENT + pinfo.desegment_offset = offset + break end elseif (version == 0xfd) then if (buffer:len() - 2 - offset > 10) then @@ -544,9 +490,9 @@ def generate_packet_dis(outf): offset = offset + 3 else -- handle truncated header - local hsize = buffer:len() - 2 - offset - subtree:add(f.rawheader, buffer(offset, hsize)) - offset = offset + hsize + pinfo.desegment_len = DESEGMENT_ONE_MORE_SEGMENT + pinfo.desegment_offset = offset + break end end @@ -631,11 +577,17 @@ def generate_epilog(outf): wtap_encap = DissectorTable.get("wtap_encap") wtap_encap:add(wtap.USER0, mavlink_proto) --- bind protocol dissector to port 14550 and 14580 +-- bind protocol dissector to ports: 14550, 14580, 18570 local udp_dissector_table = DissectorTable.get("udp.port") udp_dissector_table:add(14550, mavlink_proto) udp_dissector_table:add(14580, mavlink_proto) +udp_dissector_table:add(18570, mavlink_proto) + +-- register common Mavlink TCP ports + +DissectorTable.get("tcp.port"):add("5760-5763", mavlink_proto) + """) def generate(basename, xml): @@ -675,11 +627,11 @@ def generate(basename, xml): generate_msg_fields(outf, m, enums) for e in enums: - if e.is_flags: + if e.bitmask: generate_flag_enum_dissector(outf, e) for m in msgs: - generate_payload_dissector(outf, m, cmds) + generate_payload_dissector(outf, m, cmds, enums) generate_packet_dis(outf) # generate_enums(outf, enums) @@ -690,4 +642,3 @@ def generate(basename, xml): generate_epilog(outf) outf.close() print("Generated %s OK" % filename) -