diff --git a/ExtLibs/ArduPilot/CurrentState.cs b/ExtLibs/ArduPilot/CurrentState.cs index 2815f62f85..09afd1d889 100644 --- a/ExtLibs/ArduPilot/CurrentState.cs +++ b/ExtLibs/ArduPilot/CurrentState.cs @@ -392,6 +392,22 @@ public float altasl [GroupText("Position")] public float gpsyaw { get; private set; } + [DisplayText("GPS System Errors")] + [GroupText("Position")] + public uint gpssystem_errors { get; private set; } + + [DisplayText("GPS Authentication Status")] + [GroupText("Position")] + public byte gpsauthentication_state { get; private set; } + + [DisplayText("GPS Jamming Status")] + [GroupText("Position")] + public byte gpsjamming_state { get; private set; } + + [DisplayText("GPS Spoofing Status")] + [GroupText("Position")] + public byte gpsspoofing_state { get; private set; } + [DisplayText("Latitude2 (dd)")] [GroupText("Position")] public double lat2 { get; set; } @@ -3049,6 +3065,11 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi gpsyaw = -1; } + gpssystem_errors = gps.system_errors; + gpsauthentication_state = gps.authentication_state; + gpsjamming_state = gps.jamming_state; + gpsspoofing_state = gps.spoofing_state; + //MAVLink.packets[(byte)MAVLink.MSG_NAMES.GPS_RAW); } diff --git a/ExtLibs/Mavlink/Mavlink.cs b/ExtLibs/Mavlink/Mavlink.cs index ed5d08c4cc..d575c9d351 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 = "Wed Jan 17 2024"; + public const string MAVLINK_BUILD_DATE = "Thu May 02 2024"; public const string MAVLINK_WIRE_PROTOCOL_VERSION = "2.0"; public const int MAVLINK_MAX_PAYLOAD_LEN = 255; @@ -37,6 +37,7 @@ public partial class MAVLink // msgid, name, crc, minlength, length, type public static message_info[] MAVLINK_MESSAGE_INFOS = new message_info[] { + new message_info(26900, "VIDEO_STREAM_INFORMATION99", 222, 246, 246, typeof( mavlink_video_stream_information99_t )), new message_info(1, "SYS_STATUS", 124, 31, 31, typeof( mavlink_sys_status_t )), new message_info(2, "SYSTEM_TIME", 137, 12, 12, typeof( mavlink_system_time_t )), new message_info(4, "PING", 237, 14, 14, typeof( mavlink_ping_t )), @@ -48,7 +49,7 @@ public partial class MAVLink new message_info(21, "PARAM_REQUEST_LIST", 159, 2, 2, typeof( mavlink_param_request_list_t )), new message_info(22, "PARAM_VALUE", 220, 25, 25, typeof( mavlink_param_value_t )), new message_info(23, "PARAM_SET", 168, 23, 23, typeof( mavlink_param_set_t )), - new message_info(24, "GPS_RAW_INT", 24, 30, 52, typeof( mavlink_gps_raw_int_t )), + new message_info(24, "GPS_RAW_INT", 24, 30, 59, typeof( mavlink_gps_raw_int_t )), new message_info(25, "GPS_STATUS", 23, 101, 101, typeof( mavlink_gps_status_t )), new message_info(26, "SCALED_IMU", 170, 22, 24, typeof( mavlink_scaled_imu_t )), new message_info(27, "RAW_IMU", 144, 26, 29, typeof( mavlink_raw_imu_t )), @@ -328,12 +329,11 @@ public partial class MAVLink new message_info(50005, "CUBEPILOT_FIRMWARE_UPDATE_RESP", 152, 6, 6, typeof( mavlink_cubepilot_firmware_update_resp_t )), new message_info(52000, "AIRLINK_AUTH", 13, 100, 100, typeof( mavlink_airlink_auth_t )), new message_info(52001, "AIRLINK_AUTH_RESPONSE", 239, 1, 1, typeof( mavlink_airlink_auth_response_t )), - new message_info(26900, "VIDEO_STREAM_INFORMATION99", 222, 246, 246, typeof( mavlink_video_stream_information99_t )), new message_info(0, "HEARTBEAT", 50, 9, 9, typeof( mavlink_heartbeat_t )), }; - public const byte MAVLINK_VERSION = 2; + public const byte MAVLINK_VERSION = 3; public const byte MAVLINK_IFLAG_SIGNED= 0x01; public const byte MAVLINK_IFLAG_MASK = 0x01; @@ -366,6 +366,7 @@ public override string ToString() public enum MAVLINK_MSG_ID { + VIDEO_STREAM_INFORMATION99 = 26900, SYS_STATUS = 1, SYSTEM_TIME = 2, PING = 4, @@ -657,11 +658,11 @@ public enum MAVLINK_MSG_ID CUBEPILOT_FIRMWARE_UPDATE_RESP = 50005, AIRLINK_AUTH = 52000, AIRLINK_AUTH_RESPONSE = 52001, - VIDEO_STREAM_INFORMATION99 = 26900, HEARTBEAT = 0, } + /// public enum ACCELCAL_VEHICLE_POS: int /*default*/ { @@ -2473,7 +2474,6 @@ public enum OSD_PARAM_CONFIG_ERROR: byte }; - /// These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. public enum FIRMWARE_VERSION_TYPE: int /*default*/ { @@ -5811,6 +5811,93 @@ public enum MISSION_STATE: byte }; + /// Flags indicating errors in a GPS receiver. + [Flags] + public enum GPS_SYSTEM_ERROR_FLAGS: uint + { + /// There are no errors in the GPS receiver. | + [Description("There are no errors in the GPS receiver.")] + GPS_SYSTEM_ERROR_NONE=0, + /// There are problems with incoming correction streams. | + [Description("There are problems with incoming correction streams.")] + GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS=1, + /// There are problems with the configuration. | + [Description("There are problems with the configuration.")] + GPS_SYSTEM_ERROR_CONFIGURATION=2, + /// There are problems with the software on the GPS receiver. | + [Description("There are problems with the software on the GPS receiver.")] + GPS_SYSTEM_ERROR_SOFTWARE=4, + /// There are problems with an antenna connected to the GPS receiver. | + [Description("There are problems with an antenna connected to the GPS receiver.")] + GPS_SYSTEM_ERROR_ANTENNA=8, + /// There are problems handling all incoming events. | + [Description("There are problems handling all incoming events.")] + GPS_SYSTEM_ERROR_EVENT_CONGESTION=16, + /// The GPS receiver CPU is overloaded. | + [Description("The GPS receiver CPU is overloaded.")] + GPS_SYSTEM_ERROR_CPU_OVERLOAD=32, + /// The GPS receiver is experiencing output congestion. | + [Description("The GPS receiver is experiencing output congestion.")] + GPS_SYSTEM_ERROR_OUTPUT_CONGESTION=64, + + }; + + /// Signal authentication state in a GPS receiver. + public enum GPS_AUTHENTICATION_STATE: byte + { + /// The GPS receiver does not provide GPS signal authentication info. | + [Description("The GPS receiver does not provide GPS signal authentication info.")] + UNKNOWN=0, + /// The GPS receiver is initializing signal authentication. | + [Description("The GPS receiver is initializing signal authentication.")] + INITIALIZING=1, + /// The GPS receiver encountered an error while initializing signal authentication. | + [Description("The GPS receiver encountered an error while initializing signal authentication.")] + ERROR=2, + /// The GPS receiver has correctly authenticated all signals. | + [Description("The GPS receiver has correctly authenticated all signals.")] + OK=3, + /// GPS signal authentication is disabled on the receiver. | + [Description("GPS signal authentication is disabled on the receiver.")] + DISABLED=4, + + }; + + /// Signal jamming state in a GPS receiver. + public enum GPS_JAMMING_STATE: byte + { + /// The GPS receiver does not provide GPS signal jamming info. | + [Description("The GPS receiver does not provide GPS signal jamming info.")] + UNKNOWN=0, + /// The GPS receiver detected no signal jamming. | + [Description("The GPS receiver detected no signal jamming.")] + OK=1, + /// The GPS receiver detected and mitigated signal jamming. | + [Description("The GPS receiver detected and mitigated signal jamming.")] + MITIGATED=2, + /// The GPS receiver detected signal jamming. | + [Description("The GPS receiver detected signal jamming.")] + DETECTED=3, + }; + + /// Signal spoofing state in a GPS receiver. + public enum GPS_SPOOFING_STATE: byte + { + /// The GPS receiver does not provide GPS signal spoofing info. | + [Description("The GPS receiver does not provide GPS signal spoofing info.")] + UNKNOWN=0, + /// The GPS receiver detected no signal spoofing. | + [Description("The GPS receiver detected no signal spoofing.")] + OK=1, + /// The GPS receiver detected signal spoofing. | + [Description("The GPS receiver detected signal spoofing.")] + DETECTED=2, + /// The GPS receiver detected and mitigated signal spoofing. | + [Description("The GPS receiver detected and mitigated signal spoofing.")] + MITIGATED=3, + + }; + /// State flags for ADS-B transponder dynamic report public enum UAVIONIX_ADSB_OUT_DYNAMIC_STATE: ushort @@ -6938,6 +7025,94 @@ public enum MAV_COMPONENT: int /*default*/ }; + [Obsolete] + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=246)] + /// Information about video stream + public struct mavlink_video_stream_information99_t + { + /// packet ordered constructor + public mavlink_video_stream_information99_t(float framerate,uint bitrate,ushort resolution_h,ushort resolution_v,ushort rotation,byte camera_id,byte status,byte[] uri) + { + this.framerate = framerate; + this.bitrate = bitrate; + this.resolution_h = resolution_h; + this.resolution_v = resolution_v; + this.rotation = rotation; + this.camera_id = camera_id; + this.status = status; + this.uri = uri; + + } + + /// packet xml order + public static mavlink_video_stream_information99_t PopulateXMLOrder(byte camera_id,byte status,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,byte[] uri) + { + var msg = new mavlink_video_stream_information99_t(); + + msg.camera_id = camera_id; + msg.status = status; + msg.framerate = framerate; + msg.resolution_h = resolution_h; + msg.resolution_v = resolution_v; + msg.bitrate = bitrate; + msg.rotation = rotation; + msg.uri = uri; + + return msg; + } + + + /// Frame rate. [Hz] + [Units("[Hz]")] + [Description("Frame rate.")] + //[FieldOffset(0)] + public float framerate; + + /// Bit rate. [bits/s] + [Units("[bits/s]")] + [Description("Bit rate.")] + //[FieldOffset(4)] + public uint bitrate; + + /// Horizontal resolution. [pix] + [Units("[pix]")] + [Description("Horizontal resolution.")] + //[FieldOffset(8)] + public ushort resolution_h; + + /// Vertical resolution. [pix] + [Units("[pix]")] + [Description("Vertical resolution.")] + //[FieldOffset(10)] + public ushort resolution_v; + + /// Video image rotation clockwise. [deg] + [Units("[deg]")] + [Description("Video image rotation clockwise.")] + //[FieldOffset(12)] + public ushort rotation; + + /// Video Stream ID (1 for first, 2 for second, etc.) + [Units("")] + [Description("Video Stream ID (1 for first, 2 for second, etc.)")] + //[FieldOffset(14)] + public byte camera_id; + + /// Number of streams available. + [Units("")] + [Description("Number of streams available.")] + //[FieldOffset(15)] + public byte status; + + /// Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). + [Units("")] + [Description("Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).")] + //[FieldOffset(16)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=230)] + public byte[] uri; + }; + [Obsolete] /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)] @@ -12245,94 +12420,6 @@ public static mavlink_esc_telemetry_29_to_32_t PopulateXMLOrder(byte[] temperatu public byte[] temperature; }; - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=246)] - /// Information about video stream - public struct mavlink_video_stream_information99_t - { - /// packet ordered constructor - public mavlink_video_stream_information99_t(float framerate,uint bitrate,ushort resolution_h,ushort resolution_v,ushort rotation,byte camera_id,byte status,byte[] uri) - { - this.framerate = framerate; - this.bitrate = bitrate; - this.resolution_h = resolution_h; - this.resolution_v = resolution_v; - this.rotation = rotation; - this.camera_id = camera_id; - this.status = status; - this.uri = uri; - - } - - /// packet xml order - public static mavlink_video_stream_information99_t PopulateXMLOrder(byte camera_id,byte status,float framerate,ushort resolution_h,ushort resolution_v,uint bitrate,ushort rotation,byte[] uri) - { - var msg = new mavlink_video_stream_information99_t(); - - msg.camera_id = camera_id; - msg.status = status; - msg.framerate = framerate; - msg.resolution_h = resolution_h; - msg.resolution_v = resolution_v; - msg.bitrate = bitrate; - msg.rotation = rotation; - msg.uri = uri; - - return msg; - } - - - /// Frame rate. [Hz] - [Units("[Hz]")] - [Description("Frame rate.")] - //[FieldOffset(0)] - public float framerate; - - /// Bit rate. [bits/s] - [Units("[bits/s]")] - [Description("Bit rate.")] - //[FieldOffset(4)] - public uint bitrate; - - /// Horizontal resolution. [pix] - [Units("[pix]")] - [Description("Horizontal resolution.")] - //[FieldOffset(8)] - public ushort resolution_h; - - /// Vertical resolution. [pix] - [Units("[pix]")] - [Description("Vertical resolution.")] - //[FieldOffset(10)] - public ushort resolution_v; - - /// Video image rotation clockwise. [deg] - [Units("[deg]")] - [Description("Video image rotation clockwise.")] - //[FieldOffset(12)] - public ushort rotation; - - /// Video Stream ID (1 for first, 2 for second, etc.) - [Units("")] - [Description("Video Stream ID (1 for first, 2 for second, etc.)")] - //[FieldOffset(14)] - public byte camera_id; - - /// Number of streams available. - [Units("")] - [Description("Number of streams available.")] - //[FieldOffset(15)] - public byte status; - - /// Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - [Units("")] - [Description("Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).")] - //[FieldOffset(16)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=230)] - public byte[] uri; - }; - /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)] @@ -12961,12 +13048,12 @@ public static mavlink_param_set_t PopulateXMLOrder(byte target_system,byte targe /// extensions_start 10 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=52)] + [StructLayout(LayoutKind.Sequential,Pack=1,Size=59)] /// The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. public struct mavlink_gps_raw_int_t { /// packet ordered constructor - public mavlink_gps_raw_int_t(ulong time_usec,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,/*GPS_FIX_TYPE*/byte fix_type,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw) + public mavlink_gps_raw_int_t(ulong time_usec,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,/*GPS_FIX_TYPE*/byte fix_type,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw,/*GPS_SYSTEM_ERROR_FLAGS*/uint system_errors,/*GPS_AUTHENTICATION_STATE*/byte authentication_state,/*GPS_JAMMING_STATE*/byte jamming_state,/*GPS_SPOOFING_STATE*/byte spoofing_state) { this.time_usec = time_usec; this.lat = lat; @@ -12984,11 +13071,15 @@ public mavlink_gps_raw_int_t(ulong time_usec,int lat,int lon,int alt,ushort eph, this.vel_acc = vel_acc; this.hdg_acc = hdg_acc; this.yaw = yaw; + this.system_errors = system_errors; + this.authentication_state = authentication_state; + this.jamming_state = jamming_state; + this.spoofing_state = spoofing_state; } /// packet xml order - public static mavlink_gps_raw_int_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_TYPE*/byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw) + public static mavlink_gps_raw_int_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_TYPE*/byte fix_type,int lat,int lon,int alt,ushort eph,ushort epv,ushort vel,ushort cog,byte satellites_visible,int alt_ellipsoid,uint h_acc,uint v_acc,uint vel_acc,uint hdg_acc,ushort yaw,/*GPS_SYSTEM_ERROR_FLAGS*/uint system_errors,/*GPS_AUTHENTICATION_STATE*/byte authentication_state,/*GPS_JAMMING_STATE*/byte jamming_state,/*GPS_SPOOFING_STATE*/byte spoofing_state) { var msg = new mavlink_gps_raw_int_t(); @@ -13008,6 +13099,10 @@ public static mavlink_gps_raw_int_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_T msg.vel_acc = vel_acc; msg.hdg_acc = hdg_acc; msg.yaw = yaw; + msg.system_errors = system_errors; + msg.authentication_state = authentication_state; + msg.jamming_state = jamming_state; + msg.spoofing_state = spoofing_state; return msg; } @@ -13108,6 +13203,30 @@ public static mavlink_gps_raw_int_t PopulateXMLOrder(ulong time_usec,/*GPS_FIX_T [Description("Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.")] //[FieldOffset(50)] public ushort yaw; + + /// Errors in the GPS system GPS_SYSTEM_ERROR_FLAGS bitmask + [Units("")] + [Description("Errors in the GPS system")] + //[FieldOffset(52)] + public /*GPS_SYSTEM_ERROR_FLAGS*/uint system_errors; + + /// Signal authentication state of the GPS system GPS_AUTHENTICATION_STATE + [Units("")] + [Description("Signal authentication state of the GPS system")] + //[FieldOffset(56)] + public /*GPS_AUTHENTICATION_STATE*/byte authentication_state; + + /// Signal jamming state of the GPS system GPS_JAMMING_STATE + [Units("")] + [Description("Signal jamming state of the GPS system")] + //[FieldOffset(57)] + public /*GPS_JAMMING_STATE*/byte jamming_state; + + /// Signal spoofing state of the GPS system GPS_SPOOFING_STATE + [Units("")] + [Description("Signal spoofing state of the GPS system")] + //[FieldOffset(58)] + public /*GPS_SPOOFING_STATE*/byte spoofing_state; }; diff --git a/ExtLibs/Mavlink/mavlink.lua b/ExtLibs/Mavlink/mavlink.lua index c6b3556565..7e6590a309 100644 --- a/ExtLibs/Mavlink/mavlink.lua +++ b/ExtLibs/Mavlink/mavlink.lua @@ -20,6 +20,7 @@ protocolVersions = { } messageName = { + [26900] = 'VIDEO_STREAM_INFORMATION99', [150] = 'SENSOR_OFFSETS', [151] = 'SET_MAG_OFFSETS', [152] = 'MEMINFO', @@ -92,7 +93,6 @@ messageName = { [11042] = 'ESC_TELEMETRY_21_TO_24', [11043] = 'ESC_TELEMETRY_25_TO_28', [11044] = 'ESC_TELEMETRY_29_TO_32', - [26900] = 'VIDEO_STREAM_INFORMATION99', [1] = 'SYS_STATUS', [2] = 'SYSTEM_TIME', [4] = 'PING', @@ -2003,6 +2003,35 @@ local enumEntryName = { [4] = "MISSION_STATE_PAUSED", [5] = "MISSION_STATE_COMPLETE", }, + ["GPS_SYSTEM_ERROR_FLAGS"] = { + [0] = "GPS_SYSTEM_ERROR_NONE", + [1] = "GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS", + [2] = "GPS_SYSTEM_ERROR_CONFIGURATION", + [4] = "GPS_SYSTEM_ERROR_SOFTWARE", + [8] = "GPS_SYSTEM_ERROR_ANTENNA", + [16] = "GPS_SYSTEM_ERROR_EVENT_CONGESTION", + [32] = "GPS_SYSTEM_ERROR_CPU_OVERLOAD", + [64] = "GPS_SYSTEM_ERROR_OUTPUT_CONGESTION", + }, + ["GPS_AUTHENTICATION_STATE"] = { + [0] = "GPS_AUTHENTICATION_STATE_UNKNOWN", + [1] = "GPS_AUTHENTICATION_STATE_INITIALIZING", + [2] = "GPS_AUTHENTICATION_STATE_ERROR", + [3] = "GPS_AUTHENTICATION_STATE_OK", + [4] = "GPS_AUTHENTICATION_STATE_DISABLED", + }, + ["GPS_JAMMING_STATE"] = { + [0] = "GPS_JAMMING_STATE_UNKNOWN", + [1] = "GPS_JAMMING_STATE_OK", + [2] = "GPS_JAMMING_STATE_MITIGATED", + [3] = "GPS_JAMMING_STATE_DETECTED", + }, + ["GPS_SPOOFING_STATE"] = { + [0] = "GPS_SPOOFING_STATE_UNKNOWN", + [1] = "GPS_SPOOFING_STATE_OK", + [2] = "GPS_SPOOFING_STATE_DETECTED", + [3] = "GPS_SPOOFING_STATE_MITIGATED", + }, ["UAVIONIX_ADSB_OUT_DYNAMIC_STATE"] = { [1] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE", [2] = "UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED", @@ -3062,6 +3091,15 @@ f.cmd_MAV_CMD_EXTERNAL_POSITION_ESTIMATE_param6 = ProtoField.new("param6: Longit 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.VIDEO_STREAM_INFORMATION99_camera_id = ProtoField.new("camera_id (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_camera_id", ftypes.UINT8, nil) +f.VIDEO_STREAM_INFORMATION99_status = ProtoField.new("status (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_status", ftypes.UINT8, nil) +f.VIDEO_STREAM_INFORMATION99_framerate = ProtoField.new("framerate (float)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_framerate", ftypes.FLOAT, nil) +f.VIDEO_STREAM_INFORMATION99_resolution_h = ProtoField.new("resolution_h (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_resolution_h", ftypes.UINT16, nil) +f.VIDEO_STREAM_INFORMATION99_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_resolution_v", ftypes.UINT16, nil) +f.VIDEO_STREAM_INFORMATION99_bitrate = ProtoField.new("bitrate (uint32_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_bitrate", ftypes.UINT32, nil) +f.VIDEO_STREAM_INFORMATION99_rotation = ProtoField.new("rotation (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_rotation", ftypes.UINT16, nil) +f.VIDEO_STREAM_INFORMATION99_uri = ProtoField.new("uri (char)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_uri", ftypes.STRING, 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) f.SENSOR_OFFSETS_mag_ofs_z = ProtoField.new("mag_ofs_z (int16_t)", "mavlink_proto.SENSOR_OFFSETS_mag_ofs_z", ftypes.INT16, nil) @@ -4887,15 +4925,6 @@ f.ESC_TELEMETRY_29_TO_32_count_1 = ProtoField.new("count[1] (uint16_t)", "mavlin f.ESC_TELEMETRY_29_TO_32_count_2 = ProtoField.new("count[2] (uint16_t)", "mavlink_proto.ESC_TELEMETRY_29_TO_32_count_2", ftypes.UINT16, nil) f.ESC_TELEMETRY_29_TO_32_count_3 = ProtoField.new("count[3] (uint16_t)", "mavlink_proto.ESC_TELEMETRY_29_TO_32_count_3", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_camera_id = ProtoField.new("camera_id (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_camera_id", ftypes.UINT8, nil) -f.VIDEO_STREAM_INFORMATION99_status = ProtoField.new("status (uint8_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_status", ftypes.UINT8, nil) -f.VIDEO_STREAM_INFORMATION99_framerate = ProtoField.new("framerate (float)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_framerate", ftypes.FLOAT, nil) -f.VIDEO_STREAM_INFORMATION99_resolution_h = ProtoField.new("resolution_h (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_resolution_h", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_resolution_v = ProtoField.new("resolution_v (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_resolution_v", ftypes.UINT16, nil) -f.VIDEO_STREAM_INFORMATION99_bitrate = ProtoField.new("bitrate (uint32_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_bitrate", ftypes.UINT32, nil) -f.VIDEO_STREAM_INFORMATION99_rotation = ProtoField.new("rotation (uint16_t)", "mavlink_proto.VIDEO_STREAM_INFORMATION99_rotation", ftypes.UINT16, nil) -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", 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) @@ -5062,6 +5091,17 @@ f.GPS_RAW_INT_v_acc = ProtoField.new("v_acc (uint32_t)", "mavlink_proto.GPS_RAW_ f.GPS_RAW_INT_vel_acc = ProtoField.new("vel_acc (uint32_t)", "mavlink_proto.GPS_RAW_INT_vel_acc", ftypes.UINT32, nil) f.GPS_RAW_INT_hdg_acc = ProtoField.new("hdg_acc (uint32_t)", "mavlink_proto.GPS_RAW_INT_hdg_acc", ftypes.UINT32, nil) f.GPS_RAW_INT_yaw = ProtoField.new("yaw (uint16_t)", "mavlink_proto.GPS_RAW_INT_yaw", ftypes.UINT16, nil) +f.GPS_RAW_INT_system_errors = ProtoField.new("system_errors (GPS_SYSTEM_ERROR_FLAGS)", "mavlink_proto.GPS_RAW_INT_system_errors", ftypes.UINT32, nil) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_INCOMING_CORRECTIONS = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS", "GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS", 7, nil, 1) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_CONFIGURATION = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_CONFIGURATION", "GPS_SYSTEM_ERROR_CONFIGURATION", 7, nil, 2) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_SOFTWARE = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_SOFTWARE", "GPS_SYSTEM_ERROR_SOFTWARE", 7, nil, 4) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_ANTENNA = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_ANTENNA", "GPS_SYSTEM_ERROR_ANTENNA", 7, nil, 8) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_EVENT_CONGESTION = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_EVENT_CONGESTION", "GPS_SYSTEM_ERROR_EVENT_CONGESTION", 7, nil, 16) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_CPU_OVERLOAD = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_CPU_OVERLOAD", "GPS_SYSTEM_ERROR_CPU_OVERLOAD", 7, nil, 32) +f.GPS_RAW_INT_system_errors_flagGPS_SYSTEM_ERROR_OUTPUT_CONGESTION = ProtoField.bool("mavlink_proto.GPS_RAW_INT_system_errors.GPS_SYSTEM_ERROR_OUTPUT_CONGESTION", "GPS_SYSTEM_ERROR_OUTPUT_CONGESTION", 7, nil, 64) +f.GPS_RAW_INT_authentication_state = ProtoField.new("authentication_state (GPS_AUTHENTICATION_STATE)", "mavlink_proto.GPS_RAW_INT_authentication_state", ftypes.UINT8, enumEntryName.GPS_AUTHENTICATION_STATE) +f.GPS_RAW_INT_jamming_state = ProtoField.new("jamming_state (GPS_JAMMING_STATE)", "mavlink_proto.GPS_RAW_INT_jamming_state", ftypes.UINT8, enumEntryName.GPS_JAMMING_STATE) +f.GPS_RAW_INT_spoofing_state = ProtoField.new("spoofing_state (GPS_SPOOFING_STATE)", "mavlink_proto.GPS_RAW_INT_spoofing_state", ftypes.UINT8, enumEntryName.GPS_SPOOFING_STATE) f.GPS_STATUS_satellites_visible = ProtoField.new("satellites_visible (uint8_t)", "mavlink_proto.GPS_STATUS_satellites_visible", ftypes.UINT8, nil) f.GPS_STATUS_satellite_prn_0 = ProtoField.new("satellite_prn[0] (uint8_t)", "mavlink_proto.GPS_STATUS_satellite_prn_0", ftypes.UINT8, nil) @@ -11093,6 +11133,16 @@ function dissect_flags_MAV_WINCH_STATUS_FLAG(tree, name, tvbrange, value) tree:add_le(f[name .. "_flagMAV_WINCH_STATUS_CLUTCH_ENGAGED"], tvbrange, value) end -- dissect flag field +function dissect_flags_GPS_SYSTEM_ERROR_FLAGS(tree, name, tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_INCOMING_CORRECTIONS"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_CONFIGURATION"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_SOFTWARE"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_ANTENNA"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_EVENT_CONGESTION"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_CPU_OVERLOAD"], tvbrange, value) + tree:add_le(f[name .. "_flagGPS_SYSTEM_ERROR_OUTPUT_CONGESTION"], tvbrange, value) +end +-- dissect flag field 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) @@ -11166,6 +11216,41 @@ function dissect_flags_MAV_MODE_FLAG_DECODE_POSITION(tree, name, 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 VIDEO_STREAM_INFORMATION99 +function payload_fns.payload_26900(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 246 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 246) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + 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 SENSOR_OFFSETS function payload_fns.payload_150(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange @@ -17151,41 +17236,6 @@ function payload_fns.payload_11044(buffer, tree, msgid, offset, limit, pinfo) 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, tvbrange - if (offset + 246 > limit) then - padded = buffer(0, limit):bytes() - padded:set_size(offset + 246) - padded = padded:tvb("Untruncated payload") - else - padded = buffer - end - 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, tvbrange @@ -17451,9 +17501,9 @@ 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, tvbrange - if (offset + 52 > limit) then + if (offset + 59 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 52) + padded:set_size(offset + 59) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -17506,6 +17556,19 @@ function payload_fns.payload_24(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 50, 2) value = tvbrange:le_uint() subtree = tree:add_le(f.GPS_RAW_INT_yaw, tvbrange, value) + tvbrange = padded(offset + 52, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_system_errors, tvbrange, value) + dissect_flags_GPS_SYSTEM_ERROR_FLAGS(subtree, "GPS_RAW_INT_system_errors", tvbrange, value) + tvbrange = padded(offset + 56, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_authentication_state, tvbrange, value) + tvbrange = padded(offset + 57, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_jamming_state, tvbrange, value) + tvbrange = padded(offset + 58, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GPS_RAW_INT_spoofing_state, tvbrange, value) end -- dissect payload of message type GPS_STATUS function payload_fns.payload_25(buffer, tree, msgid, offset, limit, pinfo) diff --git a/ExtLibs/Mavlink/message_definitions/common.xml b/ExtLibs/Mavlink/message_definitions/common.xml index 769078adbf..2d16976592 100644 --- a/ExtLibs/Mavlink/message_definitions/common.xml +++ b/ExtLibs/Mavlink/message_definitions/common.xml @@ -4123,6 +4123,81 @@ Mission has executed all mission items. + + Flags indicating errors in a GPS receiver. + + There are no errors in the GPS receiver. + + + There are problems with incoming correction streams. + + + There are problems with the configuration. + + + There are problems with the software on the GPS receiver. + + + There are problems with an antenna connected to the GPS receiver. + + + There are problems handling all incoming events. + + + The GPS receiver CPU is overloaded. + + + The GPS receiver is experiencing output congestion. + + + + Signal authentication state in a GPS receiver. + + The GPS receiver does not provide GPS signal authentication info. + + + The GPS receiver is initializing signal authentication. + + + The GPS receiver encountered an error while initializing signal authentication. + + + The GPS receiver has correctly authenticated all signals. + + + GPS signal authentication is disabled on the receiver. + + + + Signal jamming state in a GPS receiver. + + The GPS receiver does not provide GPS signal jamming info. + + + The GPS receiver detected no signal jamming. + + + The GPS receiver detected and mitigated signal jamming. + + + The GPS receiver detected signal jamming. + + + + Signal spoofing state in a GPS receiver. + + The GPS receiver does not provide GPS signal spoofing info. + + + The GPS receiver detected no signal spoofing. + + + The GPS receiver detected and mitigated signal spoofing. + + + The GPS receiver detected signal spoofing. + + @@ -4230,6 +4305,10 @@ Speed uncertainty. Heading / track uncertainty Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. + Errors in the GPS system + Signal authentication state of the GPS system + Signal jamming state of the GPS system + Signal spoofing state of the GPS system The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.