diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 087965da4e..0d566d5d0e 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/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.