Skip to content

Commit

Permalink
build: patches: Add improve_support_gimbal_device_attitude_status
Browse files Browse the repository at this point in the history
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
  • Loading branch information
patrickelectric committed Jul 17, 2024
1 parent f6f76d2 commit d838bb2
Showing 1 changed file with 48 additions and 0 deletions.
48 changes: 48 additions & 0 deletions build/patches/improve_support_gimbal_device_attitude_status.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index 1ccad646..509cfc37 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -6478,18 +6478,34 @@
<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>
</message>
<message id="285" name="GIMBAL_DEVICE_ATTITUDE_STATUS">
- <wip/>
- <!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
- <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>
+ <description>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.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
- <field type="uint16_t" name="flags" enum="GIMBAL_DEVICE_FLAGS">Current gimbal flags set.</field>
- <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>
- <field type="float" name="angular_velocity_x" units="rad/s">X component of angular velocity (NaN if unknown)</field>
- <field type="float" name="angular_velocity_y" units="rad/s">Y component of angular velocity (NaN if unknown)</field>
- <field type="float" name="angular_velocity_z" units="rad/s">Z component of angular velocity (NaN if unknown)</field>
- <field type="uint32_t" name="failure_flags" display="bitmask" enum="GIMBAL_DEVICE_ERROR_FLAGS">Failure flags (0 for no failure)</field>
+ <field type="uint16_t" name="flags">Current gimbal flags set.</field>
+ <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>
+ <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>
+ <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>
+ <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>
+ <field type="uint32_t" name="failure_flags">Failure flags (0 for no failure)</field>
+ <extensions/>
+ <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>
+ <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>
+ <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>
</message>
<message id="286" name="AUTOPILOT_STATE_FOR_GIMBAL_DEVICE">
<wip/>

0 comments on commit d838bb2

Please sign in to comment.