diff --git a/ExtLibs/Mavlink/Mavlink.cs b/ExtLibs/Mavlink/Mavlink.cs index c3888f71f6..b99664459c 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 = "Sat Jul 15 2023"; + public const string MAVLINK_BUILD_DATE = "Wed Aug 16 2023"; public const string MAVLINK_WIRE_PROTOCOL_VERSION = "2.0"; public const int MAVLINK_MAX_PAYLOAD_LEN = 255; @@ -227,7 +227,7 @@ public partial class MAVLink new message_info(256, "SETUP_SIGNING", 71, 42, 42, typeof( mavlink_setup_signing_t )), new message_info(257, "BUTTON_CHANGE", 131, 9, 9, typeof( mavlink_button_change_t )), new message_info(258, "PLAY_TUNE", 187, 32, 232, typeof( mavlink_play_tune_t )), - new message_info(259, "CAMERA_INFORMATION", 92, 235, 235, typeof( mavlink_camera_information_t )), + new message_info(259, "CAMERA_INFORMATION", 92, 235, 236, typeof( mavlink_camera_information_t )), new message_info(260, "CAMERA_SETTINGS", 146, 5, 13, typeof( mavlink_camera_settings_t )), new message_info(261, "STORAGE_INFORMATION", 179, 27, 60, typeof( mavlink_storage_information_t )), new message_info(262, "CAMERA_CAPTURE_STATUS", 12, 18, 22, typeof( mavlink_camera_capture_status_t )), @@ -245,11 +245,12 @@ public partial class MAVLink 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(283, "GIMBAL_DEVICE_INFORMATION", 74, 144, 145, 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(285, "GIMBAL_DEVICE_ATTITUDE_STATUS", 137, 40, 49, typeof( mavlink_gimbal_device_attitude_status_t )), + new message_info(286, "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 210, 53, 57, 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(288, "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 20, 23, 23, typeof( mavlink_gimbal_manager_set_manual_control_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 )), @@ -268,6 +269,7 @@ public partial class MAVLink new message_info(370, "SMART_BATTERY_INFO", 75, 87, 109, typeof( mavlink_smart_battery_info_t )), new message_info(373, "GENERATOR_STATUS", 117, 42, 42, typeof( mavlink_generator_status_t )), new message_info(375, "ACTUATOR_OUTPUT_STATUS", 251, 140, 140, typeof( mavlink_actuator_output_status_t )), + new message_info(376, "RELAY_STATUS", 199, 8, 8, typeof( mavlink_relay_status_t )), new message_info(385, "TUNNEL", 147, 133, 133, typeof( mavlink_tunnel_t )), new message_info(386, "CAN_FRAME", 132, 16, 16, typeof( mavlink_can_frame_t )), new message_info(387, "CANFD_FRAME", 4, 72, 72, typeof( mavlink_canfd_frame_t )), @@ -324,6 +326,8 @@ public partial class MAVLink new message_info(50003, "HERELINK_TELEM", 62, 19, 19, typeof( mavlink_herelink_telem_t )), new message_info(50004, "CUBEPILOT_FIRMWARE_UPDATE_START", 240, 10, 10, typeof( mavlink_cubepilot_firmware_update_start_t )), 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 )), @@ -575,6 +579,7 @@ public enum MAVLINK_MSG_ID GIMBAL_DEVICE_ATTITUDE_STATUS = 285, AUTOPILOT_STATE_FOR_GIMBAL_DEVICE = 286, GIMBAL_MANAGER_SET_PITCHYAW = 287, + GIMBAL_MANAGER_SET_MANUAL_CONTROL = 288, WIFI_CONFIG_AP = 299, AIS_VESSEL = 301, UAVCAN_NODE_STATUS = 310, @@ -593,6 +598,7 @@ public enum MAVLINK_MSG_ID SMART_BATTERY_INFO = 370, GENERATOR_STATUS = 373, ACTUATOR_OUTPUT_STATUS = 375, + RELAY_STATUS = 376, TUNNEL = 385, CAN_FRAME = 386, CANFD_FRAME = 387, @@ -649,6 +655,8 @@ public enum MAVLINK_MSG_ID HERELINK_TELEM = 50003, CUBEPILOT_FIRMWARE_UPDATE_START = 50004, CUBEPILOT_FIRMWARE_UPDATE_RESP = 50005, + AIRLINK_AUTH = 52000, + AIRLINK_AUTH_RESPONSE = 52001, VIDEO_STREAM_INFORMATION99 = 26900, HEARTBEAT = 0, } @@ -1054,13 +1062,11 @@ public enum MAV_CMD: ushort /// Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. |Target tag to jump to.| Repeat count.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| [Description("Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number.")] DO_JUMP_TAG=601, - /// 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. |Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| Pitch rate (positive to pitch up).| Yaw rate (positive to yaw to the right).| Gimbal manager flags to use.| 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("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] + /// Set gimbal manager pitch/yaw setpoints (low rate command). 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: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. |Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| Pitch rate (positive to pitch up).| Yaw rate (positive to yaw to the right).| Gimbal manager flags to use.| 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("Set gimbal manager pitch/yaw setpoints (low rate command). 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: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. ")] 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.")] @@ -2891,46 +2897,52 @@ public enum MAV_MOUNT_MODE: byte }; - /// Gimbal device (low level) capability flags (bitmap) + /// Gimbal device (low level) capability flags (bitmap). [Flags] public enum GIMBAL_DEVICE_CAP_FLAGS: ushort { - /// Gimbal device supports a retracted position | - [Description("Gimbal device supports a retracted position")] + /// Gimbal device supports a retracted position. | + [Description("Gimbal device supports a retracted position.")] HAS_RETRACT=1, - /// Gimbal device supports a horizontal, forward looking position, stabilized | - [Description("Gimbal device supports a horizontal, forward looking position, stabilized")] + /// Gimbal device supports a horizontal, forward looking position, stabilized. | + [Description("Gimbal device supports a horizontal, forward looking position, stabilized.")] HAS_NEUTRAL=2, /// Gimbal device supports rotating around roll axis. | [Description("Gimbal device supports rotating around roll axis.")] HAS_ROLL_AXIS=4, - /// Gimbal device supports to follow a roll angle relative to the vehicle | - [Description("Gimbal device supports to follow a roll angle relative to the vehicle")] + /// Gimbal device supports to follow a roll angle relative to the vehicle. | + [Description("Gimbal device supports to follow a roll angle relative to the vehicle.")] HAS_ROLL_FOLLOW=8, - /// Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized) | - [Description("Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized)")] + /// Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized). | + [Description("Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized).")] HAS_ROLL_LOCK=16, /// Gimbal device supports rotating around pitch axis. | [Description("Gimbal device supports rotating around pitch axis.")] HAS_PITCH_AXIS=32, - /// Gimbal device supports to follow a pitch angle relative to the vehicle | - [Description("Gimbal device supports to follow a pitch angle relative to the vehicle")] + /// Gimbal device supports to follow a pitch angle relative to the vehicle. | + [Description("Gimbal device supports to follow a pitch angle relative to the vehicle.")] HAS_PITCH_FOLLOW=64, - /// Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized) | - [Description("Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized)")] + /// Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized). | + [Description("Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized).")] HAS_PITCH_LOCK=128, /// Gimbal device supports rotating around yaw axis. | [Description("Gimbal device supports rotating around yaw axis.")] HAS_YAW_AXIS=256, - /// Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default) | - [Description("Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)")] + /// Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). | + [Description("Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default).")] HAS_YAW_FOLLOW=512, - /// Gimbal device supports locking to an absolute heading (often this is an option available) | - [Description("Gimbal device supports locking to an absolute heading (often this is an option available)")] + /// Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available). | + [Description("Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available).")] HAS_YAW_LOCK=1024, /// Gimbal device supports yawing/panning infinetely (e.g. using slip disk). | [Description("Gimbal device supports yawing/panning infinetely (e.g. using slip disk).")] SUPPORTS_INFINITE_YAW=2048, + /// Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME. | + [Description("Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME.")] + SUPPORTS_YAW_IN_EARTH_FRAME=4096, + /// Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation. | + [Description("Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation.")] + HAS_RC_INPUTS=8192, }; @@ -2996,18 +3008,33 @@ public enum GIMBAL_DEVICE_FLAGS: ushort /// Set to retracted safe position (no stabilization), takes presedence over all other flags. | [Description("Set to retracted safe position (no stabilization), takes presedence over all other flags.")] RETRACT=1, - /// Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (pitch=yaw=0) but may be any orientation. | - [Description("Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (pitch=yaw=0) but may be any orientation.")] + /// Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation. | + [Description("Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation.")] NEUTRAL=2, - /// Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal. | - [Description("Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal.")] + /// Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. | + [Description("Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.")] ROLL_LOCK=4, - /// Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default. | - [Description("Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default.")] + /// Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. | + [Description("Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.")] PITCH_LOCK=8, - /// Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). | - [Description("Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle).")] + /// Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward). | + [Description("Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward).")] YAW_LOCK=16, + /// Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward). | + [Description("Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward).")] + YAW_IN_VEHICLE_FRAME=32, + /// Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North). | + [Description("Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North).")] + YAW_IN_EARTH_FRAME=64, + /// Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored). | + [Description("Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored).")] + ACCEPTS_YAW_IN_EARTH_FRAME=128, + /// The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored. | + [Description("The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored.")] + RC_EXCLUSIVE=256, + /// The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation. | + [Description("The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation.")] + RC_MIXED=512, }; @@ -3015,21 +3042,36 @@ public enum GIMBAL_DEVICE_FLAGS: ushort [Flags] public enum GIMBAL_MANAGER_FLAGS: uint { - /// Based on GIMBAL_DEVICE_FLAGS_RETRACT | - [Description("Based on GIMBAL_DEVICE_FLAGS_RETRACT")] + /// Based on GIMBAL_DEVICE_FLAGS_RETRACT. | + [Description("Based on GIMBAL_DEVICE_FLAGS_RETRACT.")] RETRACT=1, - /// Based on GIMBAL_DEVICE_FLAGS_NEUTRAL | - [Description("Based on GIMBAL_DEVICE_FLAGS_NEUTRAL")] + /// Based on GIMBAL_DEVICE_FLAGS_NEUTRAL. | + [Description("Based on GIMBAL_DEVICE_FLAGS_NEUTRAL.")] NEUTRAL=2, - /// Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK | - [Description("Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK")] + /// Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK. | + [Description("Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK.")] ROLL_LOCK=4, - /// Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK | - [Description("Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK")] + /// Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK. | + [Description("Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK.")] PITCH_LOCK=8, - /// Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK | - [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK")] + /// Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK. | + [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK.")] YAW_LOCK=16, + /// Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME. | + [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME.")] + YAW_IN_VEHICLE_FRAME=32, + /// Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. | + [Description("Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.")] + YAW_IN_EARTH_FRAME=64, + /// Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME. | + [Description("Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME.")] + ACCEPTS_YAW_IN_EARTH_FRAME=128, + /// Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE. | + [Description("Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE.")] + RC_EXCLUSIVE=256, + /// Based on GIMBAL_DEVICE_FLAGS_RC_MIXED. | + [Description("Based on GIMBAL_DEVICE_FLAGS_RC_MIXED.")] + RC_MIXED=512, }; @@ -3052,8 +3094,8 @@ public enum GIMBAL_DEVICE_ERROR_FLAGS: uint /// There is an error with the gimbal power source. | [Description("There is an error with the gimbal power source.")] POWER_ERROR=16, - /// There is an error with the gimbal motor's. | - [Description("There is an error with the gimbal motor's.")] + /// There is an error with the gimbal motors. | + [Description("There is an error with the gimbal motors.")] MOTOR_ERROR=32, /// There is an error with the gimbal's software. | [Description("There is an error with the gimbal's software.")] @@ -3061,9 +3103,12 @@ public enum GIMBAL_DEVICE_ERROR_FLAGS: uint /// There is an error with the gimbal's communication. | [Description("There is an error with the gimbal's communication.")] COMMS_ERROR=128, - /// Gimbal is currently calibrating. | - [Description("Gimbal is currently calibrating.")] + /// Gimbal device is currently calibrating. | + [Description("Gimbal device is currently calibrating.")] CALIBRATION_RUNNING=256, + /// Gimbal device is not assigned to a gimbal manager. | + [Description("Gimbal device is not assigned to a gimbal manager.")] + NO_MANAGER=512, }; @@ -6152,6 +6197,19 @@ public enum ICAROUS_FMS_STATE: byte + /// + public enum AIRLINK_AUTH_RESPONSE_TYPE: byte + { + /// Login or password error | + [Description("Login or password error")] + AIRLINK_ERROR_LOGIN_OR_PASS=0, + /// Auth successful | + [Description("Auth successful")] + AIRLINK_AUTH_OK=1, + + }; + + /// Micro air vehicle / autopilot classes. This identifies the individual model. public enum MAV_AUTOPILOT: byte { @@ -24978,13 +25036,13 @@ public static mavlink_play_tune_t PopulateXMLOrder(byte target_system,byte targe }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=235)] + /// extensions_start 13 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=236)] /// Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. public struct mavlink_camera_information_t { /// packet ordered constructor - public mavlink_camera_information_t(uint time_boot_ms,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,/*CAMERA_CAP_FLAGS*/uint flags,ushort resolution_h,ushort resolution_v,ushort cam_definition_version,byte[] vendor_name,byte[] model_name,byte lens_id,byte[] cam_definition_uri) + public mavlink_camera_information_t(uint time_boot_ms,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,/*CAMERA_CAP_FLAGS*/uint flags,ushort resolution_h,ushort resolution_v,ushort cam_definition_version,byte[] vendor_name,byte[] model_name,byte lens_id,byte[] cam_definition_uri,byte gimbal_device_id) { this.time_boot_ms = time_boot_ms; this.firmware_version = firmware_version; @@ -24999,11 +25057,12 @@ public mavlink_camera_information_t(uint time_boot_ms,uint firmware_version,floa this.model_name = model_name; this.lens_id = lens_id; this.cam_definition_uri = cam_definition_uri; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,ushort resolution_h,ushort resolution_v,byte lens_id,/*CAMERA_CAP_FLAGS*/uint flags,ushort cam_definition_version,byte[] cam_definition_uri) + public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,uint firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,ushort resolution_h,ushort resolution_v,byte lens_id,/*CAMERA_CAP_FLAGS*/uint flags,ushort cam_definition_version,byte[] cam_definition_uri,byte gimbal_device_id) { var msg = new mavlink_camera_information_t(); @@ -25020,6 +25079,7 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by msg.flags = flags; msg.cam_definition_version = cam_definition_version; msg.cam_definition_uri = cam_definition_uri; + msg.gimbal_device_id = gimbal_device_id; return msg; } @@ -25105,6 +25165,12 @@ public static mavlink_camera_information_t PopulateXMLOrder(uint time_boot_ms,by //[FieldOffset(95)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=140)] public byte[] cam_definition_uri; + + /// Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. + [Units("")] + [Description("Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.")] + //[FieldOffset(235)] + public byte gimbal_device_id; }; @@ -26317,7 +26383,7 @@ 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. @@ -26405,14 +26471,14 @@ public static mavlink_gimbal_manager_information_t PopulateXMLOrder(uint time_bo //[FieldOffset(28)] public float yaw_max; - /// Gimbal device ID that this gimbal manager is responsible for. + /// Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). [Units("")] - [Description("Gimbal device ID that this gimbal manager is responsible for.")] + [Description("Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] //[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). @@ -26460,9 +26526,9 @@ public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms //[FieldOffset(4)] public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Gimbal device ID that this gimbal manager is responsible for. + /// Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). [Units("")] - [Description("Gimbal device ID that this gimbal manager is responsible for.")] + [Description("Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).")] //[FieldOffset(8)] public byte gimbal_device_id; @@ -26493,12 +26559,100 @@ public static mavlink_gimbal_manager_status_t PopulateXMLOrder(uint time_boot_ms /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=144)] + [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] + /// High level message to control a gimbal's attitude. 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_attitude_t + { + /// packet ordered constructor + public mavlink_gimbal_manager_set_attitude_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,byte target_system,byte target_component,byte gimbal_device_id) + { + this.flags = flags; + this.q = q; + this.angular_velocity_x = angular_velocity_x; + this.angular_velocity_y = angular_velocity_y; + this.angular_velocity_z = angular_velocity_z; + 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_attitude_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) + { + var msg = new mavlink_gimbal_manager_set_attitude_t(); + + msg.target_system = target_system; + msg.target_component = target_component; + msg.flags = flags; + msg.gimbal_device_id = gimbal_device_id; + msg.q = q; + msg.angular_velocity_x = angular_velocity_x; + msg.angular_velocity_y = angular_velocity_y; + msg.angular_velocity_z = angular_velocity_z; + + 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; + + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) + [Units("")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)")] + //[FieldOffset(4)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] + public float[] q; + + /// X component of angular velocity, positive is rolling to the right, NaN to be ignored. [rad/s] + [Units("[rad/s]")] + [Description("X component of angular velocity, positive is rolling to the right, NaN to be ignored.")] + //[FieldOffset(20)] + public float angular_velocity_x; + + /// Y component of angular velocity, positive is pitching up, NaN to be ignored. [rad/s] + [Units("[rad/s]")] + [Description("Y component of angular velocity, positive is pitching up, NaN to be ignored.")] + //[FieldOffset(24)] + public float angular_velocity_y; + + /// Z component of angular velocity, positive is yawing to the right, NaN to be ignored. [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity, positive is yawing to the right, NaN to be ignored.")] + //[FieldOffset(28)] + public float angular_velocity_z; + + /// System ID + [Units("")] + [Description("System ID")] + //[FieldOffset(32)] + public byte target_system; + + /// Component ID + [Units("")] + [Description("Component ID")] + //[FieldOffset(33)] + 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(34)] + public byte gimbal_device_id; + }; + + + /// extensions_start 15 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=145)] /// 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.. public struct mavlink_gimbal_device_information_t { /// packet ordered constructor - public mavlink_gimbal_device_information_t(ulong uid,uint time_boot_ms,uint firmware_version,uint hardware_version,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,byte[] vendor_name,byte[] model_name,byte[] custom_name) + public mavlink_gimbal_device_information_t(ulong uid,uint time_boot_ms,uint firmware_version,uint hardware_version,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,byte[] vendor_name,byte[] model_name,byte[] custom_name,byte gimbal_device_id) { this.uid = uid; this.time_boot_ms = time_boot_ms; @@ -26515,11 +26669,12 @@ public mavlink_gimbal_device_information_t(ulong uid,uint time_boot_ms,uint firm this.vendor_name = vendor_name; this.model_name = model_name; this.custom_name = custom_name; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,byte[] custom_name,uint firmware_version,uint hardware_version,ulong uid,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) + public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boot_ms,byte[] vendor_name,byte[] model_name,byte[] custom_name,uint firmware_version,uint hardware_version,ulong uid,/*GIMBAL_DEVICE_CAP_FLAGS*/ushort cap_flags,ushort custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,byte gimbal_device_id) { var msg = new mavlink_gimbal_device_information_t(); @@ -26538,6 +26693,7 @@ public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boo msg.pitch_max = pitch_max; msg.yaw_min = yaw_min; msg.yaw_max = yaw_max; + msg.gimbal_device_id = gimbal_device_id; return msg; } @@ -26567,39 +26723,39 @@ public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boo //[FieldOffset(16)] public uint hardware_version; - /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + /// Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] + [Description("Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.")] //[FieldOffset(20)] public float roll_min; - /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) [rad] + /// Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)")] + [Description("Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.")] //[FieldOffset(24)] public float roll_max; - /// Minimum hardware pitch angle (positive: up, negative: down) [rad] + /// Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] [Units("[rad]")] - [Description("Minimum hardware pitch angle (positive: up, negative: down)")] + [Description("Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] //[FieldOffset(28)] public float pitch_min; - /// Maximum hardware pitch angle (positive: up, negative: down) [rad] + /// Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. [rad] [Units("[rad]")] - [Description("Maximum hardware pitch angle (positive: up, negative: down)")] + [Description("Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.")] //[FieldOffset(32)] public float pitch_max; - /// Minimum hardware yaw angle (positive: to the right, negative: to the left) [rad] + /// Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Minimum hardware yaw angle (positive: to the right, negative: to the left)")] + [Description("Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.")] //[FieldOffset(36)] public float yaw_min; - /// Maximum hardware yaw angle (positive: to the right, negative: to the left) [rad] + /// Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. [rad] [Units("[rad]")] - [Description("Maximum hardware yaw angle (positive: to the right, negative: to the left)")] + [Description("Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.")] //[FieldOffset(40)] public float yaw_max; @@ -26635,12 +26791,18 @@ public static mavlink_gimbal_device_information_t PopulateXMLOrder(uint time_boo //[FieldOffset(112)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)] public byte[] custom_name; + + /// This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. + [Units("")] + [Description("This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.")] + //[FieldOffset(144)] + public byte gimbal_device_id; }; - [Obsolete] + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)] - /// Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. Angles and rates can be set to NaN according to use case. + /// Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. The quaternion and angular velocities can be set to NaN according to use case. For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. These rules are to ensure backwards compatibility. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. public struct mavlink_gimbal_device_set_attitude_t { /// packet ordered constructor @@ -26673,28 +26835,28 @@ public static mavlink_gimbal_device_set_attitude_t PopulateXMLOrder(byte target_ } - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used) + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored.")] //[FieldOffset(0)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// X component of angular velocity, positive is rolling to the right, NaN to be ignored. [rad/s] + /// X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. [rad/s] [Units("[rad/s]")] - [Description("X component of angular velocity, positive is rolling to the right, NaN to be ignored.")] + [Description("X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(16)] public float angular_velocity_x; - /// Y component of angular velocity, positive is pitching up, NaN to be ignored. [rad/s] + /// Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. [rad/s] [Units("[rad/s]")] - [Description("Y component of angular velocity, positive is pitching up, NaN to be ignored.")] + [Description("Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(20)] public float angular_velocity_y; - /// Z component of angular velocity, positive is yawing to the right, NaN to be ignored. [rad/s] + /// Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. [rad/s] [Units("[rad/s]")] - [Description("Z component of angular velocity, positive is yawing to the right, NaN to be ignored.")] + [Description("Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored.")] //[FieldOffset(24)] public float angular_velocity_z; @@ -26717,14 +26879,14 @@ public static mavlink_gimbal_device_set_attitude_t PopulateXMLOrder(byte target_ public byte target_component; }; - [Obsolete] - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=40)] - /// Message reporting the status of a gimbal device. This message should be broadcasted by a gimbal device component. The angles encoded in the quaternion are relative to absolute North if the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set (roll: positive is rolling to the right, pitch: positive is pitching up, yaw is turn to the right) or relative to the vehicle heading if the flag is not set. This message should be broadcast at a low regular rate (e.g. 10Hz). + + /// extensions_start 9 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=49)] + /// Message reporting the status of a gimbal device. This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Other conditions of the flags are not allowed. The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN. public struct mavlink_gimbal_device_attitude_status_t { /// packet ordered constructor - public mavlink_gimbal_device_attitude_status_t(uint time_boot_ms,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags,/*GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component) + public mavlink_gimbal_device_attitude_status_t(uint time_boot_ms,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags,/*GIMBAL_DEVICE_FLAGS*/ushort flags,byte target_system,byte target_component,float delta_yaw,float delta_yaw_velocity,byte gimbal_device_id) { this.time_boot_ms = time_boot_ms; this.q = q; @@ -26735,11 +26897,14 @@ public mavlink_gimbal_device_attitude_status_t(uint time_boot_ms,float[] q,float this.flags = flags; this.target_system = target_system; this.target_component = target_component; + this.delta_yaw = delta_yaw; + this.delta_yaw_velocity = delta_yaw_velocity; + this.gimbal_device_id = gimbal_device_id; } /// packet xml order - public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte target_system,byte target_component,uint time_boot_ms,/*GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags) + public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte target_system,byte target_component,uint time_boot_ms,/*GIMBAL_DEVICE_FLAGS*/ushort flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,/*GIMBAL_DEVICE_ERROR_FLAGS*/uint failure_flags,float delta_yaw,float delta_yaw_velocity,byte gimbal_device_id) { var msg = new mavlink_gimbal_device_attitude_status_t(); @@ -26752,6 +26917,9 @@ public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte targ msg.angular_velocity_y = angular_velocity_y; msg.angular_velocity_z = angular_velocity_z; msg.failure_flags = failure_flags; + msg.delta_yaw = delta_yaw; + msg.delta_yaw_velocity = delta_yaw_velocity; + msg.gimbal_device_id = gimbal_device_id; return msg; } @@ -26763,28 +26931,28 @@ public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte targ //[FieldOffset(0)] public uint time_boot_ms; - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set) + /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)")] + [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description.")] //[FieldOffset(4)] [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// X component of angular velocity (NaN if unknown) [rad/s] + /// X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. [rad/s] [Units("[rad/s]")] - [Description("X component of angular velocity (NaN if unknown)")] + [Description("X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown.")] //[FieldOffset(20)] public float angular_velocity_x; - /// Y component of angular velocity (NaN if unknown) [rad/s] + /// Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. [rad/s] [Units("[rad/s]")] - [Description("Y component of angular velocity (NaN if unknown)")] + [Description("Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown.")] //[FieldOffset(24)] public float angular_velocity_y; - /// Z component of angular velocity (NaN if unknown) [rad/s] + /// Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. [rad/s] [Units("[rad/s]")] - [Description("Z component of angular velocity (NaN if unknown)")] + [Description("Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown.")] //[FieldOffset(28)] public float angular_velocity_z; @@ -26811,16 +26979,34 @@ public static mavlink_gimbal_device_attitude_status_t PopulateXMLOrder(byte targ [Description("Component ID")] //[FieldOffset(39)] public byte target_component; + + /// Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. [rad] + [Units("[rad]")] + [Description("Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown.")] + //[FieldOffset(40)] + public float delta_yaw; + + /// Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. [rad/s] + [Units("[rad/s]")] + [Description("Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.")] + //[FieldOffset(44)] + public float delta_yaw_velocity; + + /// This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. + [Units("")] + [Description("This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.")] + //[FieldOffset(48)] + public byte gimbal_device_id; }; - /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=53)] - /// Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the gimbal manager to the gimbal device component. The data of this message server for the gimbal's estimator corrections in particular horizon compensation, as well as the autopilot's control intention e.g. feed forward angular control in z-axis. + /// extensions_start 12 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=57)] + /// Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis. public struct mavlink_autopilot_state_for_gimbal_device_t { /// packet ordered constructor - public mavlink_autopilot_state_for_gimbal_device_t(ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,byte target_system,byte target_component,/*MAV_LANDED_STATE*/byte landed_state) + public mavlink_autopilot_state_for_gimbal_device_t(ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,byte target_system,byte target_component,/*MAV_LANDED_STATE*/byte landed_state,float angular_velocity_z) { this.time_boot_us = time_boot_us; this.q = q; @@ -26834,11 +27020,12 @@ public mavlink_autopilot_state_for_gimbal_device_t(ulong time_boot_us,float[] q, this.target_system = target_system; this.target_component = target_component; this.landed_state = landed_state; + this.angular_velocity_z = angular_velocity_z; } /// packet xml order - public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte target_system,byte target_component,ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,/*MAV_LANDED_STATE*/byte landed_state) + public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte target_system,byte target_component,ulong time_boot_us,float[] q,uint q_estimated_delay_us,float vx,float vy,float vz,uint v_estimated_delay_us,float feed_forward_angular_velocity_z,/*ESTIMATOR_STATUS_FLAGS*/ushort estimator_status,/*MAV_LANDED_STATE*/byte landed_state,float angular_velocity_z) { var msg = new mavlink_autopilot_state_for_gimbal_device_t(); @@ -26854,6 +27041,7 @@ public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte msg.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; msg.estimator_status = estimator_status; msg.landed_state = landed_state; + msg.angular_velocity_z = angular_velocity_z; return msg; } @@ -26872,39 +27060,39 @@ public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] public float[] q; - /// Estimated delay of the attitude data. [us] + /// Estimated delay of the attitude data. 0 if unknown. [us] [Units("[us]")] - [Description("Estimated delay of the attitude data.")] + [Description("Estimated delay of the attitude data. 0 if unknown.")] //[FieldOffset(24)] public uint q_estimated_delay_us; - /// X Speed in NED (North, East, Down). [m/s] + /// X Speed in NED (North, East, Down). NAN if unknown. [m/s] [Units("[m/s]")] - [Description("X Speed in NED (North, East, Down).")] + [Description("X Speed in NED (North, East, Down). NAN if unknown.")] //[FieldOffset(28)] public float vx; - /// Y Speed in NED (North, East, Down). [m/s] + /// Y Speed in NED (North, East, Down). NAN if unknown. [m/s] [Units("[m/s]")] - [Description("Y Speed in NED (North, East, Down).")] + [Description("Y Speed in NED (North, East, Down). NAN if unknown.")] //[FieldOffset(32)] public float vy; - /// Z Speed in NED (North, East, Down). [m/s] + /// Z Speed in NED (North, East, Down). NAN if unknown. [m/s] [Units("[m/s]")] - [Description("Z Speed in NED (North, East, Down).")] + [Description("Z Speed in NED (North, East, Down). NAN if unknown.")] //[FieldOffset(36)] public float vz; - /// Estimated delay of the speed data. [us] + /// Estimated delay of the speed data. 0 if unknown. [us] [Units("[us]")] - [Description("Estimated delay of the speed data.")] + [Description("Estimated delay of the speed data. 0 if unknown.")] //[FieldOffset(40)] public uint v_estimated_delay_us; - /// Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing. [rad/s] + /// Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. [rad/s] [Units("[rad/s]")] - [Description("Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.")] + [Description("Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing.")] //[FieldOffset(44)] public float feed_forward_angular_velocity_z; @@ -26931,22 +27119,28 @@ public static mavlink_autopilot_state_for_gimbal_device_t PopulateXMLOrder(byte [Description("The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.")] //[FieldOffset(52)] public /*MAV_LANDED_STATE*/byte landed_state; + + /// Z component of angular velocity in NED (North, East, Down). NaN if unknown. [rad/s] + [Units("[rad/s]")] + [Description("Z component of angular velocity in NED (North, East, Down). NaN if unknown.")] + //[FieldOffset(53)] + public float angular_velocity_z; }; - [Obsolete] + /// extensions_start 0 - [StructLayout(LayoutKind.Sequential,Pack=1,Size=35)] - /// High level message to control a gimbal's attitude. 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_attitude_t + [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)] + /// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. + public struct mavlink_gimbal_manager_set_pitchyaw_t { /// packet ordered constructor - public mavlink_gimbal_manager_set_attitude_t(/*GIMBAL_MANAGER_FLAGS*/uint flags,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,byte target_system,byte target_component,byte gimbal_device_id) + 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.q = q; - this.angular_velocity_x = angular_velocity_x; - this.angular_velocity_y = angular_velocity_y; - this.angular_velocity_z = angular_velocity_z; + 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; @@ -26954,18 +27148,18 @@ public mavlink_gimbal_manager_set_attitude_t(/*GIMBAL_MANAGER_FLAGS*/uint flags, } /// packet xml order - public static mavlink_gimbal_manager_set_attitude_t PopulateXMLOrder(byte target_system,byte target_component,/*GIMBAL_MANAGER_FLAGS*/uint flags,byte gimbal_device_id,float[] q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) + 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_attitude_t(); + 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.q = q; - msg.angular_velocity_x = angular_velocity_x; - msg.angular_velocity_y = angular_velocity_y; - msg.angular_velocity_z = angular_velocity_z; + msg.pitch = pitch; + msg.yaw = yaw; + msg.pitch_rate = pitch_rate; + msg.yaw_rate = yaw_rate; return msg; } @@ -26977,58 +27171,57 @@ public static mavlink_gimbal_manager_set_attitude_t PopulateXMLOrder(byte target //[FieldOffset(0)] public /*GIMBAL_MANAGER_FLAGS*/uint flags; - /// Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - [Units("")] - [Description("Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)")] + /// 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)] - [MarshalAs(UnmanagedType.ByValArray,SizeConst=4)] - public float[] q; + public float pitch; - /// X component of angular velocity, positive is rolling to the right, NaN to be ignored. [rad/s] - [Units("[rad/s]")] - [Description("X component of angular velocity, positive is rolling to the right, NaN to be ignored.")] - //[FieldOffset(20)] - public float angular_velocity_x; + /// 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; - /// Y component of angular velocity, positive is pitching up, NaN to be ignored. [rad/s] + /// Pitch angular rate (positive: up, negative: down, NaN to be ignored). [rad/s] [Units("[rad/s]")] - [Description("Y component of angular velocity, positive is pitching up, NaN to be ignored.")] - //[FieldOffset(24)] - public float angular_velocity_y; + [Description("Pitch angular rate (positive: up, negative: down, NaN to be ignored).")] + //[FieldOffset(12)] + public float pitch_rate; - /// Z component of angular velocity, positive is yawing to the right, NaN to be ignored. [rad/s] + /// Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). [rad/s] [Units("[rad/s]")] - [Description("Z component of angular velocity, positive is yawing to the right, NaN to be ignored.")] - //[FieldOffset(28)] - public float angular_velocity_z; + [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(32)] + //[FieldOffset(20)] public byte target_system; /// Component ID [Units("")] [Description("Component ID")] - //[FieldOffset(33)] + //[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(34)] + //[FieldOffset(22)] 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 + /// High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). 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_manual_control_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) + public mavlink_gimbal_manager_set_manual_control_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; @@ -27042,9 +27235,9 @@ public mavlink_gimbal_manager_set_pitchyaw_t(/*GIMBAL_MANAGER_FLAGS*/uint flags, } /// 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) + public static mavlink_gimbal_manager_set_manual_control_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(); + var msg = new mavlink_gimbal_manager_set_manual_control_t(); msg.target_system = target_system; msg.target_component = target_component; @@ -27059,33 +27252,33 @@ public static mavlink_gimbal_manager_set_pitchyaw_t PopulateXMLOrder(byte target } - /// High level gimbal manager flags to use. GIMBAL_MANAGER_FLAGS + /// High level gimbal manager flags. GIMBAL_MANAGER_FLAGS [Units("")] - [Description("High level gimbal manager flags to use.")] + [Description("High level gimbal manager flags.")] //[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).")] + /// Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). + [Units("")] + [Description("Pitch angle unitless (-1..1, 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).")] + /// Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + [Units("")] + [Description("Yaw angle unitless (-1..1, 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).")] + /// Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). + [Units("")] + [Description("Pitch angular rate unitless (-1..1, 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).")] + /// Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + [Units("")] + [Description("Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).")] //[FieldOffset(16)] public float yaw_rate; @@ -28699,6 +28892,53 @@ public static mavlink_actuator_output_status_t PopulateXMLOrder(ulong time_usec, }; + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)] + /// Reports the on/off state of relays, as controlled by MAV_CMD_DO_SET_RELAY. + public struct mavlink_relay_status_t + { + /// packet ordered constructor + public mavlink_relay_status_t(uint time_boot_ms,ushort on,ushort present) + { + this.time_boot_ms = time_boot_ms; + this.on = on; + this.present = present; + + } + + /// packet xml order + public static mavlink_relay_status_t PopulateXMLOrder(uint time_boot_ms,ushort on,ushort present) + { + var msg = new mavlink_relay_status_t(); + + msg.time_boot_ms = time_boot_ms; + msg.on = on; + msg.present = present; + + return msg; + } + + + /// Timestamp (time since system boot). [ms] + [Units("[ms]")] + [Description("Timestamp (time since system boot).")] + //[FieldOffset(0)] + public uint time_boot_ms; + + /// Relay states. Relay instance numbers are represented as individual bits in this mask by offset. bitmask + [Units("")] + [Description("Relay states. Relay instance numbers are represented as individual bits in this mask by offset.")] + //[FieldOffset(4)] + public ushort on; + + /// Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured. bitmask + [Units("")] + [Description("Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.")] + //[FieldOffset(6)] + public ushort present; + }; + + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=133)] /// Message for transporting 'arbitrary' variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification. @@ -31164,6 +31404,78 @@ public static mavlink_cubepilot_firmware_update_resp_t PopulateXMLOrder(byte tar }; + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=100)] + /// Authorization package + public struct mavlink_airlink_auth_t + { + /// packet ordered constructor + public mavlink_airlink_auth_t(byte[] login,byte[] password) + { + this.login = login; + this.password = password; + + } + + /// packet xml order + public static mavlink_airlink_auth_t PopulateXMLOrder(byte[] login,byte[] password) + { + var msg = new mavlink_airlink_auth_t(); + + msg.login = login; + msg.password = password; + + return msg; + } + + + /// Login + [Units("")] + [Description("Login")] + //[FieldOffset(0)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] login; + + /// Password + [Units("")] + [Description("Password")] + //[FieldOffset(50)] + [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)] + public byte[] password; + }; + + + /// extensions_start 0 + [StructLayout(LayoutKind.Sequential,Pack=1,Size=1)] + /// Response to the authorization request + public struct mavlink_airlink_auth_response_t + { + /// packet ordered constructor + public mavlink_airlink_auth_response_t(/*AIRLINK_AUTH_RESPONSE_TYPE*/byte resp_type) + { + this.resp_type = resp_type; + + } + + /// packet xml order + public static mavlink_airlink_auth_response_t PopulateXMLOrder(/*AIRLINK_AUTH_RESPONSE_TYPE*/byte resp_type) + { + var msg = new mavlink_airlink_auth_response_t(); + + msg.resp_type = resp_type; + + return msg; + } + + + /// Response type AIRLINK_AUTH_RESPONSE_TYPE + [Units("")] + [Description("Response type")] + //[FieldOffset(0)] + public /*AIRLINK_AUTH_RESPONSE_TYPE*/byte resp_type; + }; + + /// extensions_start 0 [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)] /// The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html diff --git a/ExtLibs/Mavlink/mavlink.lua b/ExtLibs/Mavlink/mavlink.lua index 30017a3c44..3d57875431 100644 --- a/ExtLibs/Mavlink/mavlink.lua +++ b/ExtLibs/Mavlink/mavlink.lua @@ -252,12 +252,13 @@ messageName = { [276] = 'CAMERA_TRACKING_GEO_STATUS', [280] = 'GIMBAL_MANAGER_INFORMATION', [281] = 'GIMBAL_MANAGER_STATUS', + [282] = 'GIMBAL_MANAGER_SET_ATTITUDE', [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', + [288] = 'GIMBAL_MANAGER_SET_MANUAL_CONTROL', [299] = 'WIFI_CONFIG_AP', [301] = 'AIS_VESSEL', [310] = 'UAVCAN_NODE_STATUS', @@ -276,6 +277,7 @@ messageName = { [370] = 'SMART_BATTERY_INFO', [373] = 'GENERATOR_STATUS', [375] = 'ACTUATOR_OUTPUT_STATUS', + [376] = 'RELAY_STATUS', [385] = 'TUNNEL', [386] = 'CAN_FRAME', [387] = 'CANFD_FRAME', @@ -308,6 +310,8 @@ messageName = { [50003] = 'HERELINK_TELEM', [50004] = 'CUBEPILOT_FIRMWARE_UPDATE_START', [50005] = 'CUBEPILOT_FIRMWARE_UPDATE_RESP', + [52000] = 'AIRLINK_AUTH', + [52001] = 'AIRLINK_AUTH_RESPONSE', [0] = 'HEARTBEAT', } @@ -1047,6 +1051,8 @@ local enumEntryName = { [512] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW", [1024] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK", [2048] = "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW", + [4096] = "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", + [8192] = "GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS", }, ["GIMBAL_MANAGER_CAP_FLAGS"] = { [1] = "GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT", @@ -1072,6 +1078,11 @@ local enumEntryName = { [4] = "GIMBAL_DEVICE_FLAGS_ROLL_LOCK", [8] = "GIMBAL_DEVICE_FLAGS_PITCH_LOCK", [16] = "GIMBAL_DEVICE_FLAGS_YAW_LOCK", + [32] = "GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", + [64] = "GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", + [128] = "GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", + [256] = "GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", + [512] = "GIMBAL_DEVICE_FLAGS_RC_MIXED", }, ["GIMBAL_MANAGER_FLAGS"] = { [1] = "GIMBAL_MANAGER_FLAGS_RETRACT", @@ -1079,6 +1090,11 @@ local enumEntryName = { [4] = "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", [8] = "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", [16] = "GIMBAL_MANAGER_FLAGS_YAW_LOCK", + [32] = "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", + [64] = "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", + [128] = "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", + [256] = "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", + [512] = "GIMBAL_MANAGER_FLAGS_RC_MIXED", }, ["GIMBAL_DEVICE_ERROR_FLAGS"] = { [1] = "GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT", @@ -1090,6 +1106,7 @@ local enumEntryName = { [64] = "GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR", [128] = "GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR", [256] = "GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING", + [512] = "GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", }, ["GRIPPER_ACTIONS"] = { [0] = "GRIPPER_ACTION_RELEASE", @@ -2113,6 +2130,10 @@ local enumEntryName = { [4] = "ICAROUS_FMS_STATE_APPROACH", [5] = "ICAROUS_FMS_STATE_LAND", }, + ["AIRLINK_AUTH_RESPONSE_TYPE"] = { + [0] = "AIRLINK_ERROR_LOGIN_OR_PASS", + [1] = "AIRLINK_AUTH_OK", + }, ["MAV_AUTOPILOT"] = { [0] = "MAV_AUTOPILOT_GENERIC", [1] = "MAV_AUTOPILOT_RESERVED", @@ -2785,11 +2806,16 @@ 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", 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_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", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 16) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.cmd_MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW_param5.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) 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) @@ -8419,6 +8445,7 @@ f.CAMERA_INFORMATION_flags_flagCAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = ProtoFi 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) +f.CAMERA_INFORMATION_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.CAMERA_INFORMATION_gimbal_device_id", ftypes.UINT8, nil) f.CAMERA_SETTINGS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.CAMERA_SETTINGS_time_boot_ms", ftypes.UINT32, nil) f.CAMERA_SETTINGS_mode_id = ProtoField.new("mode_id (CAMERA_MODE)", "mavlink_proto.CAMERA_SETTINGS_mode_id", ftypes.UINT8, enumEntryName.CAMERA_MODE) @@ -9081,17 +9108,44 @@ f.GIMBAL_MANAGER_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlin 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_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 16) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_STATUS_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_STATUS_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) 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_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", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 16) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_SET_ATTITUDE_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) +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) +f.GIMBAL_MANAGER_SET_ATTITUDE_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_2", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_3", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x", ftypes.FLOAT, nil) +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_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) @@ -9100,18 +9154,20 @@ 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", 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_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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, 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", 14, nil, 2048) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME", 14, nil, 4096) +f.GIMBAL_DEVICE_INFORMATION_cap_flags_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_INFORMATION_cap_flags.GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS", "GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS", 14, nil, 8192) 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) @@ -9119,15 +9175,21 @@ f.GIMBAL_DEVICE_INFORMATION_pitch_min = ProtoField.new("pitch_min (float)", "mav f.GIMBAL_DEVICE_INFORMATION_pitch_max = ProtoField.new("pitch_max (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_pitch_max", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_INFORMATION_yaw_min = ProtoField.new("yaw_min (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_yaw_min", ftypes.FLOAT, nil) f.GIMBAL_DEVICE_INFORMATION_yaw_max = ProtoField.new("yaw_max (float)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_yaw_max", ftypes.FLOAT, nil) +f.GIMBAL_DEVICE_INFORMATION_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_INFORMATION_gimbal_device_id", ftypes.UINT8, nil) 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", 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_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 16) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_DEVICE_SET_ATTITUDE_flags_flagGIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_SET_ATTITUDE_flags.GIMBAL_DEVICE_FLAGS_RC_MIXED", "GIMBAL_DEVICE_FLAGS_RC_MIXED", 10, nil, 512) 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) @@ -9140,11 +9202,16 @@ 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", 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_flags_flagGIMBAL_DEVICE_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RETRACT", "GIMBAL_DEVICE_FLAGS_RETRACT", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 16) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", "GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_flags_flagGIMBAL_DEVICE_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_flags.GIMBAL_DEVICE_FLAGS_RC_MIXED", "GIMBAL_DEVICE_FLAGS_RC_MIXED", 10, nil, 512) 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) @@ -9153,15 +9220,19 @@ 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", 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.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", 10, 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", 10, 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", 10, 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", 10, 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", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 256) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags_flagGIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = ProtoField.bool("mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_failure_flags.GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", "GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER", 10, nil, 512) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw = ProtoField.new("delta_yaw (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw", ftypes.FLOAT, nil) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw_velocity = ProtoField.new("delta_yaw_velocity (float)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw_velocity", ftypes.FLOAT, nil) +f.GIMBAL_DEVICE_ATTITUDE_STATUS_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_DEVICE_ATTITUDE_STATUS_gimbal_device_id", ftypes.UINT8, nil) 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) @@ -9190,38 +9261,46 @@ f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_estimator_status_flagESTIMATOR_PRED_POS_HORI 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", 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) -f.GIMBAL_MANAGER_SET_ATTITUDE_q_2 = ProtoField.new("q[2] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_2", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_q_3 = ProtoField.new("q[3] (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_q_3", ftypes.FLOAT, nil) -f.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x = ProtoField.new("angular_velocity_x (float)", "mavlink_proto.GIMBAL_MANAGER_SET_ATTITUDE_angular_velocity_x", ftypes.FLOAT, nil) -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.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_angular_velocity_z = ProtoField.new("angular_velocity_z (float)", "mavlink_proto.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_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_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, 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", 10, 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", 10, 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", 10, 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", 10, nil, 16) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_SET_PITCHYAW_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_PITCHYAW_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) 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.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_system", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_target_component", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags = ProtoField.new("flags (GIMBAL_MANAGER_FLAGS)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags", ftypes.UINT32, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_RETRACT = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_RETRACT", "GIMBAL_MANAGER_FLAGS_RETRACT", 10, nil, 1) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_NEUTRAL = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_NEUTRAL", "GIMBAL_MANAGER_FLAGS_NEUTRAL", 10, nil, 2) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_ROLL_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_ROLL_LOCK", "GIMBAL_MANAGER_FLAGS_ROLL_LOCK", 10, nil, 4) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_PITCH_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_PITCH_LOCK", "GIMBAL_MANAGER_FLAGS_PITCH_LOCK", 10, nil, 8) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_YAW_LOCK = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_YAW_LOCK", "GIMBAL_MANAGER_FLAGS_YAW_LOCK", 10, nil, 16) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME", 10, nil, 32) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME", 10, nil, 64) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", "GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME", 10, nil, 128) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", "GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE", 10, nil, 256) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags_flagGIMBAL_MANAGER_FLAGS_RC_MIXED = ProtoField.bool("mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags.GIMBAL_MANAGER_FLAGS_RC_MIXED", "GIMBAL_MANAGER_FLAGS_RC_MIXED", 10, nil, 512) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_gimbal_device_id = ProtoField.new("gimbal_device_id (uint8_t)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_gimbal_device_id", ftypes.UINT8, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch = ProtoField.new("pitch (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw = ProtoField.new("yaw (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch_rate = ProtoField.new("pitch_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch_rate", ftypes.FLOAT, nil) +f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw_rate = ProtoField.new("yaw_rate (float)", "mavlink_proto.GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) @@ -9662,6 +9741,10 @@ f.ACTUATOR_OUTPUT_STATUS_actuator_29 = ProtoField.new("actuator[29] (float)", "m f.ACTUATOR_OUTPUT_STATUS_actuator_30 = ProtoField.new("actuator[30] (float)", "mavlink_proto.ACTUATOR_OUTPUT_STATUS_actuator_30", ftypes.FLOAT, nil) f.ACTUATOR_OUTPUT_STATUS_actuator_31 = ProtoField.new("actuator[31] (float)", "mavlink_proto.ACTUATOR_OUTPUT_STATUS_actuator_31", ftypes.FLOAT, nil) +f.RELAY_STATUS_time_boot_ms = ProtoField.new("time_boot_ms (uint32_t)", "mavlink_proto.RELAY_STATUS_time_boot_ms", ftypes.UINT32, nil) +f.RELAY_STATUS_on = ProtoField.new("on (uint16_t)", "mavlink_proto.RELAY_STATUS_on", ftypes.UINT16, nil) +f.RELAY_STATUS_present = ProtoField.new("present (uint16_t)", "mavlink_proto.RELAY_STATUS_present", ftypes.UINT16, nil) + f.TUNNEL_target_system = ProtoField.new("target_system (uint8_t)", "mavlink_proto.TUNNEL_target_system", ftypes.UINT8, nil) f.TUNNEL_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.TUNNEL_target_component", ftypes.UINT8, nil) f.TUNNEL_payload_type = ProtoField.new("payload_type (MAV_TUNNEL_PAYLOAD_TYPE)", "mavlink_proto.TUNNEL_payload_type", ftypes.UINT16, enumEntryName.MAV_TUNNEL_PAYLOAD_TYPE) @@ -10598,6 +10681,11 @@ f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_system = ProtoField.new("target_system ( f.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_component = ProtoField.new("target_component (uint8_t)", "mavlink_proto.CUBEPILOT_FIRMWARE_UPDATE_RESP_target_component", ftypes.UINT8, nil) f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset = ProtoField.new("offset (uint32_t)", "mavlink_proto.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset", ftypes.UINT32, nil) +f.AIRLINK_AUTH_login = ProtoField.new("login (char)", "mavlink_proto.AIRLINK_AUTH_login", ftypes.STRING, nil) +f.AIRLINK_AUTH_password = ProtoField.new("password (char)", "mavlink_proto.AIRLINK_AUTH_password", ftypes.STRING, nil) + +f.AIRLINK_AUTH_RESPONSE_resp_type = ProtoField.new("resp_type (AIRLINK_AUTH_RESPONSE_TYPE)", "mavlink_proto.AIRLINK_AUTH_RESPONSE_resp_type", ftypes.UINT8, enumEntryName.AIRLINK_AUTH_RESPONSE_TYPE) + 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) @@ -10713,6 +10801,8 @@ function dissect_flags_GIMBAL_DEVICE_CAP_FLAGS(tree, name, 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) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS"], tvbrange, value) end -- dissect flag field function dissect_flags_GIMBAL_MANAGER_CAP_FLAGS(tree, name, tvbrange, value) @@ -10740,6 +10830,11 @@ function dissect_flags_GIMBAL_DEVICE_FLAGS(tree, name, 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) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_FLAGS_RC_MIXED"], tvbrange, value) end -- dissect flag field function dissect_flags_GIMBAL_MANAGER_FLAGS(tree, name, tvbrange, value) @@ -10748,6 +10843,11 @@ function dissect_flags_GIMBAL_MANAGER_FLAGS(tree, name, 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) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE"], tvbrange, value) + tree:add_le(f[name .. "_flagGIMBAL_MANAGER_FLAGS_RC_MIXED"], tvbrange, value) end -- dissect flag field function dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, tvbrange, value) @@ -10760,6 +10860,7 @@ function dissect_flags_GIMBAL_DEVICE_ERROR_FLAGS(tree, name, 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) + tree:add_le(f[name .. "_flagGIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER"], tvbrange, value) end -- dissect flag field function dissect_flags_AUTOTUNE_AXIS(tree, name, tvbrange, value) @@ -45220,9 +45321,9 @@ 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, tvbrange - if (offset + 235 > limit) then + if (offset + 236 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 235) + padded:set_size(offset + 236) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -45453,6 +45554,9 @@ function payload_fns.payload_259(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 95, 140) value = tvbrange:string() subtree = tree:add_le(f.CAMERA_INFORMATION_cam_definition_uri, tvbrange, value) + tvbrange = padded(offset + 235, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.CAMERA_INFORMATION_gimbal_device_id, tvbrange, value) end -- dissect payload of message type CAMERA_SETTINGS function payload_fns.payload_260(buffer, tree, msgid, offset, limit, pinfo) @@ -47519,12 +47623,57 @@ function payload_fns.payload_281(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.GIMBAL_MANAGER_STATUS_secondary_control_compid, 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, 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 + 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_DEVICE_INFORMATION function payload_fns.payload_283(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange - if (offset + 144 > limit) then + if (offset + 145 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 144) + padded:set_size(offset + 145) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -47575,6 +47724,9 @@ function payload_fns.payload_283(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 40, 4) value = tvbrange:le_float() subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_yaw_max, tvbrange, value) + tvbrange = padded(offset + 144, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_INFORMATION_gimbal_device_id, tvbrange, value) end -- dissect payload of message type GIMBAL_DEVICE_SET_ATTITUDE function payload_fns.payload_284(buffer, tree, msgid, offset, limit, pinfo) @@ -47621,9 +47773,9 @@ 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, tvbrange - if (offset + 40 > limit) then + if (offset + 49 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 40) + padded:set_size(offset + 49) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -47666,13 +47818,22 @@ function payload_fns.payload_285(buffer, tree, msgid, offset, limit, pinfo) 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) + tvbrange = padded(offset + 40, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw, tvbrange, value) + tvbrange = padded(offset + 44, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_delta_yaw_velocity, tvbrange, value) + tvbrange = padded(offset + 48, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.GIMBAL_DEVICE_ATTITUDE_STATUS_gimbal_device_id, 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, tvbrange - if (offset + 53 > limit) then + if (offset + 57 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 53) + padded:set_size(offset + 57) padded = padded:tvb("Untruncated payload") else padded = buffer @@ -47723,54 +47884,48 @@ function payload_fns.payload_286(buffer, tree, msgid, offset, limit, pinfo) tvbrange = padded(offset + 52, 1) value = tvbrange:le_uint() subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_landed_state, tvbrange, value) + tvbrange = padded(offset + 53, 4) + value = tvbrange:le_float() + subtree = tree:add_le(f.AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_angular_velocity_z, tvbrange, value) end --- dissect payload of message type GIMBAL_MANAGER_SET_ATTITUDE -function payload_fns.payload_282(buffer, tree, msgid, offset, limit, pinfo) +-- 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 + 35 > limit) then + if (offset + 23 > limit) then padded = buffer(0, limit):bytes() - padded:set_size(offset + 35) + padded:set_size(offset + 23) padded = padded:tvb("Untruncated payload") else padded = buffer end - tvbrange = padded(offset + 32, 1) + tvbrange = padded(offset + 20, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_ATTITUDE_target_system, tvbrange, value) - tvbrange = padded(offset + 33, 1) + 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_ATTITUDE_target_component, tvbrange, value) + 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_ATTITUDE_flags, tvbrange, value) - dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_ATTITUDE_flags", tvbrange, value) - tvbrange = padded(offset + 34, 1) + 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_ATTITUDE_gimbal_device_id, tvbrange, value) + 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_ATTITUDE_q_0, tvbrange, value) + 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_ATTITUDE_q_1, tvbrange, value) + 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_ATTITUDE_q_2, tvbrange, value) + 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_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw_rate, tvbrange, value) end --- dissect payload of message type GIMBAL_MANAGER_SET_PITCHYAW -function payload_fns.payload_287(buffer, tree, msgid, offset, limit, pinfo) +-- dissect payload of message type GIMBAL_MANAGER_SET_MANUAL_CONTROL +function payload_fns.payload_288(buffer, tree, msgid, offset, limit, pinfo) local padded, field_offset, value, subtree, tvbrange if (offset + 23 > limit) then padded = buffer(0, limit):bytes() @@ -47781,29 +47936,29 @@ function payload_fns.payload_287(buffer, tree, msgid, offset, limit, pinfo) end tvbrange = padded(offset + 20, 1) value = tvbrange:le_uint() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_target_system, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_flags, tvbrange, value) + dissect_flags_GIMBAL_MANAGER_FLAGS(subtree, "GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_pitch, tvbrange, value) tvbrange = padded(offset + 8, 4) value = tvbrange:le_float() - subtree = tree:add_le(f.GIMBAL_MANAGER_SET_PITCHYAW_yaw, tvbrange, value) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_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) + subtree = tree:add_le(f.GIMBAL_MANAGER_SET_MANUAL_CONTROL_yaw_rate, tvbrange, value) end -- dissect payload of message type WIFI_CONFIG_AP function payload_fns.payload_299(buffer, tree, msgid, offset, limit, pinfo) @@ -49140,6 +49295,26 @@ function payload_fns.payload_375(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_float() subtree = tree:add_le(f.ACTUATOR_OUTPUT_STATUS_actuator_31, tvbrange, value) end +-- dissect payload of message type RELAY_STATUS +function payload_fns.payload_376(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 8 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 8) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 4) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RELAY_STATUS_time_boot_ms, tvbrange, value) + tvbrange = padded(offset + 4, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RELAY_STATUS_on, tvbrange, value) + tvbrange = padded(offset + 6, 2) + value = tvbrange:le_uint() + subtree = tree:add_le(f.RELAY_STATUS_present, 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, tvbrange @@ -52107,6 +52282,37 @@ function payload_fns.payload_50005(buffer, tree, msgid, offset, limit, pinfo) value = tvbrange:le_uint() subtree = tree:add_le(f.CUBEPILOT_FIRMWARE_UPDATE_RESP_offset, tvbrange, value) end +-- dissect payload of message type AIRLINK_AUTH +function payload_fns.payload_52000(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 100 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 100) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 50) + value = tvbrange:string() + subtree = tree:add_le(f.AIRLINK_AUTH_login, tvbrange, value) + tvbrange = padded(offset + 50, 50) + value = tvbrange:string() + subtree = tree:add_le(f.AIRLINK_AUTH_password, tvbrange, value) +end +-- dissect payload of message type AIRLINK_AUTH_RESPONSE +function payload_fns.payload_52001(buffer, tree, msgid, offset, limit, pinfo) + local padded, field_offset, value, subtree, tvbrange + if (offset + 1 > limit) then + padded = buffer(0, limit):bytes() + padded:set_size(offset + 1) + padded = padded:tvb("Untruncated payload") + else + padded = buffer + end + tvbrange = padded(offset + 0, 1) + value = tvbrange:le_uint() + subtree = tree:add_le(f.AIRLINK_AUTH_RESPONSE_resp_type, 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, tvbrange @@ -52233,9 +52439,9 @@ function mavlink_proto.dissector(buffer,pinfo,tree) 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 @@ -52267,9 +52473,9 @@ function mavlink_proto.dissector(buffer,pinfo,tree) 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 diff --git a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml index d059979191..758cc0600a 100644 --- a/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml +++ b/ExtLibs/Mavlink/message_definitions/ardupilotmega.xml @@ -6,6 +6,7 @@ icarous.xml loweheiser.xml cubepilot.xml + csAirLink.xml 2 diff --git a/ExtLibs/Mavlink/message_definitions/common.xml b/ExtLibs/Mavlink/message_definitions/common.xml index 84b29c5202..cb8520fc13 100644 --- a/ExtLibs/Mavlink/message_definitions/common.xml +++ b/ExtLibs/Mavlink/message_definitions/common.xml @@ -400,43 +400,49 @@ - Gimbal device (low level) capability flags (bitmap) + Gimbal device (low level) capability flags (bitmap). - Gimbal device supports a retracted position + Gimbal device supports a retracted position. - Gimbal device supports a horizontal, forward looking position, stabilized + Gimbal device supports a horizontal, forward looking position, stabilized. Gimbal device supports rotating around roll axis. - Gimbal device supports to follow a roll angle relative to the vehicle + Gimbal device supports to follow a roll angle relative to the vehicle. - Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized) + Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized). Gimbal device supports rotating around pitch axis. - Gimbal device supports to follow a pitch angle relative to the vehicle + Gimbal device supports to follow a pitch angle relative to the vehicle. - Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized) + Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized). Gimbal device supports rotating around yaw axis. - Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default) + Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). - Gimbal device supports locking to an absolute heading (often this is an option available) + Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available). Gimbal device supports yawing/panning infinetely (e.g. using slip disk). + + Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME. + + + Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation. + 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. @@ -495,34 +501,64 @@ Set to retracted safe position (no stabilization), takes presedence over all other flags. - Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (pitch=yaw=0) but may be any orientation. + Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation. - Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal. + Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. - Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default. + Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. - Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle). + Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward). + + + Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward). + + + Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North). + + + Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored). + + + The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored. + + + The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation. Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS. - Based on GIMBAL_DEVICE_FLAGS_RETRACT + Based on GIMBAL_DEVICE_FLAGS_RETRACT. - Based on GIMBAL_DEVICE_FLAGS_NEUTRAL + Based on GIMBAL_DEVICE_FLAGS_NEUTRAL. - Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK + Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK. - Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK + Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK. - Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK + Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK. + + + Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME. + + + Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. + + + Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME. + + + Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE. + + + Based on GIMBAL_DEVICE_FLAGS_RC_MIXED. @@ -543,7 +579,7 @@ There is an error with the gimbal power source. - There is an error with the gimbal motor's. + There is an error with the gimbal motors. There is an error with the gimbal's software. @@ -552,7 +588,10 @@ There is an error with the gimbal's communication. - Gimbal is currently calibrating. + Gimbal device is currently calibrating. + + + Gimbal device is not assigned to a gimbal manager. @@ -1612,9 +1651,7 @@ - - - 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. + Set gimbal manager pitch/yaw setpoints (low rate command). 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: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode). Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode). Pitch rate (positive to pitch up). @@ -1623,8 +1660,6 @@ 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). @@ -5721,6 +5756,8 @@ Bitmap of camera capability flags. 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. + + Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. @@ -5879,12 +5916,10 @@ 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. + Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). 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) @@ -5893,17 +5928,26 @@ 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. + Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). 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. + + High level message to control a gimbal's attitude. 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). + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) + X component of angular velocity, positive is rolling to the right, NaN to be ignored. + 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. + 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). @@ -5915,71 +5959,85 @@ UID of gimbal hardware (0 if unknown). Bitmap of gimbal capability flags. Bitmap for use for gimbal-specific capability flags. - 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 hardware pitch angle (positive: up, negative: down) - Maximum hardware pitch angle (positive: up, negative: down) - Minimum hardware yaw angle (positive: to the right, negative: to the left) - Maximum hardware yaw angle (positive: to the right, negative: to the left) + Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. + Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. + Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. + Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. + Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. + Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. + + This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - - - Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. Angles and rates can be set to NaN according to use case. + Low level message to control a gimbal device's attitude. + This message is to be sent from the gimbal manager to the gimbal device component. + The quaternion and angular velocities can be set to NaN according to use case. + For the angles encoded in the quaternion and the angular velocities holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). + If neither of these flags are set, then (for backwards compatibility) it holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), + else they are relative to the vehicle heading (vehicle frame). + Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. + These rules are to ensure backwards compatibility. + New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. System ID Component ID Low level gimbal flags. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used) - X component of angular velocity, positive is rolling to the right, NaN to be ignored. - 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. + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. + X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. + Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. + Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - - - Message reporting the status of a gimbal device. This message should be broadcasted by a gimbal device component. The angles encoded in the quaternion are relative to absolute North if the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set (roll: positive is rolling to the right, pitch: positive is pitching up, yaw is turn to the right) or relative to the vehicle heading if the flag is not set. This message should be broadcast at a low regular rate (e.g. 10Hz). + Message reporting the status of a gimbal device. + This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). + For the angles encoded in the quaternion and the angular velocities holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). + If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). + If neither of these flags are set, then (for backwards compatibility) it holds: + If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), + else they are relative to the vehicle heading (vehicle frame). + Other conditions of the flags are not allowed. + The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as + q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). + If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, + then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. + New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, + and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN. System ID Component ID Timestamp (time since system boot). Current gimbal flags set. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set) - X component of angular velocity (NaN if unknown) - Y component of angular velocity (NaN if unknown) - Z component of angular velocity (NaN if unknown) - Failure flags (0 for no failure) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. + X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. + Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. + Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. + Failure flags (0 for no failure) + + Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. + Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. + This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the gimbal manager to the gimbal device component. The data of this message server for the gimbal's estimator corrections in particular horizon compensation, as well as the autopilot's control intention e.g. feed forward angular control in z-axis. + Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis. System ID Component ID Timestamp (time since system boot). Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - Estimated delay of the attitude data. - X Speed in NED (North, East, Down). - Y Speed in NED (North, East, Down). - Z Speed in NED (North, East, Down). - Estimated delay of the speed data. - Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing. + Estimated delay of the attitude data. 0 if unknown. + X Speed in NED (North, East, Down). NAN if unknown. + Y Speed in NED (North, East, Down). NAN if unknown. + Z Speed in NED (North, East, Down). NAN if unknown. + Estimated delay of the speed data. 0 if unknown. + Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. Bitmap indicating which estimator outputs are valid. The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - - - - - High level message to control a gimbal's attitude. 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). - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - X component of angular velocity, positive is rolling to the right, NaN to be ignored. - 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. + + Z component of angular velocity in NED (North, East, Down). NaN if unknown. - - - 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. + Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. System ID Component ID High level gimbal manager flags to use. @@ -5989,6 +6047,17 @@ 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). + + High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). 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. + 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 unitless (-1..1, positive: up, negative: down, NaN to be ignored). + Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). + Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). + Yaw angular rate unitless (-1..1, 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. @@ -6195,6 +6264,12 @@ Active outputs Servo / motor output array values. Zero values indicate unused channels. + + Reports the on/off state of relays, as controlled by MAV_CMD_DO_SET_RELAY. + Timestamp (time since system boot). + Relay states. Relay instance numbers are represented as individual bits in this mask by offset. + Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured. + Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification. System ID (can be 0 for broadcast, but this is discouraged) diff --git a/ExtLibs/Mavlink/message_definitions/csAirLink.xml b/ExtLibs/Mavlink/message_definitions/csAirLink.xml new file mode 100644 index 0000000000..063d76367e --- /dev/null +++ b/ExtLibs/Mavlink/message_definitions/csAirLink.xml @@ -0,0 +1,30 @@ + + + + + + + 3 + + + + Login or password error + + + Auth successful + + + + + + Authorization package + Login + Password + + + Response to the authorization request + Response type + + + + diff --git a/ExtLibs/Mavlink/updatexmls.bat b/ExtLibs/Mavlink/updatexmls.bat index 59614334c4..bafde026ac 100644 --- a/ExtLibs/Mavlink/updatexmls.bat +++ b/ExtLibs/Mavlink/updatexmls.bat @@ -13,4 +13,6 @@ python -c "import urllib.request; print(urllib.request.urlopen('https://github.c python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/cubepilot.xml').read().decode('utf-8') )" > message_definitions\cubepilot.xml +python -c "import urllib.request; print(urllib.request.urlopen('https://github.com/ArduPilot/mavlink/raw/master/message_definitions/v1.0/csAirLink.xml').read().decode('utf-8') )" > message_definitions\csAirLink.xml + pause \ No newline at end of file