|
| 1 | +diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml |
| 2 | +index 1ccad646..509cfc37 100644 |
| 3 | +--- a/message_definitions/v1.0/common.xml |
| 4 | ++++ b/message_definitions/v1.0/common.xml |
| 5 | +@@ -6478,18 +6478,34 @@ |
| 6 | + <field type="float" name="angular_velocity_z" units="rad/s">Z component of angular velocity, positive is panning to the right, NaN to be ignored.</field> |
| 7 | + </message> |
| 8 | + <message id="285" name="GIMBAL_DEVICE_ATTITUDE_STATUS"> |
| 9 | +- <wip/> |
| 10 | +- <!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. --> |
| 11 | +- <description>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 in the global frame (roll: positive is tilt to the right, pitch: positive is tilting up, yaw is turn to the right). This message should be broadcast at a low regular rate (e.g. 10Hz).</description> |
| 12 | ++ <description>Message reporting the status of a gimbal device. |
| 13 | ++ This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). |
| 14 | ++ For the angles encoded in the quaternion and the angular velocities holds: |
| 15 | ++ If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). |
| 16 | ++ If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). |
| 17 | ++ If neither of these flags are set, then (for backwards compatibility) it holds: |
| 18 | ++ If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), |
| 19 | ++ else they are relative to the vehicle heading (vehicle frame). |
| 20 | ++ Other conditions of the flags are not allowed. |
| 21 | ++ The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as |
| 22 | ++ q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). |
| 23 | ++ If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, |
| 24 | ++ then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. |
| 25 | ++ New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, |
| 26 | ++ and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN.</description> |
| 27 | + <field type="uint8_t" name="target_system">System ID</field> |
| 28 | + <field type="uint8_t" name="target_component">Component ID</field> |
| 29 | + <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field> |
| 30 | +- <field type="uint16_t" name="flags" enum="GIMBAL_DEVICE_FLAGS">Current gimbal flags set.</field> |
| 31 | +- <field type="float[4]" name="q">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)</field> |
| 32 | +- <field type="float" name="angular_velocity_x" units="rad/s">X component of angular velocity (NaN if unknown)</field> |
| 33 | +- <field type="float" name="angular_velocity_y" units="rad/s">Y component of angular velocity (NaN if unknown)</field> |
| 34 | +- <field type="float" name="angular_velocity_z" units="rad/s">Z component of angular velocity (NaN if unknown)</field> |
| 35 | +- <field type="uint32_t" name="failure_flags" display="bitmask" enum="GIMBAL_DEVICE_ERROR_FLAGS">Failure flags (0 for no failure)</field> |
| 36 | ++ <field type="uint16_t" name="flags">Current gimbal flags set.</field> |
| 37 | ++ <field type="float[4]" name="q">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description.</field> |
| 38 | ++ <field type="float" name="angular_velocity_x" units="rad/s" invalid="NaN">X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown.</field> |
| 39 | ++ <field type="float" name="angular_velocity_y" units="rad/s" invalid="NaN">Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown.</field> |
| 40 | ++ <field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown.</field> |
| 41 | ++ <field type="uint32_t" name="failure_flags">Failure flags (0 for no failure)</field> |
| 42 | ++ <extensions/> |
| 43 | ++ <field type="float" name="delta_yaw" units="rad" invalid="NAN">Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown.</field> |
| 44 | ++ <field type="float" name="delta_yaw_velocity" units="rad/s" invalid="NAN">Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.</field> |
| 45 | ++ <field type="uint8_t" name="gimbal_device_id" invalid="0">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.</field> |
| 46 | + </message> |
| 47 | + <message id="286" name="AUTOPILOT_STATE_FOR_GIMBAL_DEVICE"> |
| 48 | + <wip/> |
0 commit comments