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 <[email protected]>
  • Loading branch information
patrickelectric committed Jul 17, 2024
1 parent f6f76d2 commit 3ec4ef6
Showing 1 changed file with 120 additions and 0 deletions.
120 changes: 120 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,120 @@
diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index 1ccad646..6029e80e 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -1119,19 +1119,37 @@
<enum name="GIMBAL_DEVICE_FLAGS" bitmask="true">
<description>Flags for gimbal device (lower level) operation.</description>
<entry value="1" name="GIMBAL_DEVICE_FLAGS_RETRACT">
- <description>Set to retracted safe position (no stabilization), takes presedence over all other flags.</description>
+ <description>Set to retracted safe position (no stabilization), takes precedence over all other flags.</description>
</entry>
<entry value="2" name="GIMBAL_DEVICE_FLAGS_NEUTRAL">
- <description>Set to neutral position (horizontal, forward looking, with stabiliziation), takes presedence over all other flags except RETRACT.</description>
+ <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.</description>
</entry>
<entry value="4" name="GIMBAL_DEVICE_FLAGS_ROLL_LOCK">
- <description>Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal.</description>
+ <description>Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.</description>
</entry>
<entry value="8" name="GIMBAL_DEVICE_FLAGS_PITCH_LOCK">
- <description>Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default.</description>
+ <description>Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.</description>
+ </entry>
+ <entry value="12" name="BATATINHA">
+ <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).</description>
</entry>
<entry value="16" name="GIMBAL_DEVICE_FLAGS_YAW_LOCK">
- <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).</description>
+ <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).</description>
+ </entry>
+ <entry value="32" name="GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME">
+ <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).</description>
+ </entry>
+ <entry value="64" name="GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME">
+ <description>Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North).</description>
+ </entry>
+ <entry value="128" name="GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME">
+ <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).</description>
+ </entry>
+ <entry value="256" name="GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE">
+ <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.</description>
+ </entry>
+ <entry value="512" name="GIMBAL_DEVICE_FLAGS_RC_MIXED">
+ <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.</description>
</entry>
</enum>
<enum name="GIMBAL_MANAGER_FLAGS" bitmask="true">
@@ -1182,7 +1200,7 @@
<description>There is an error with the gimbal power source.</description>
</entry>
<entry value="32" name="GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR">
- <description>There is an error with the gimbal motor's.</description>
+ <description>There is an error with the gimbal motors.</description>
</entry>
<entry value="64" name="GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR">
<description>There is an error with the gimbal's software.</description>
@@ -1190,6 +1208,12 @@
<entry value="128" name="GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR">
<description>There is an error with the gimbal's communication.</description>
</entry>
+ <entry value="256" name="GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING">
+ <description>Gimbal device is currently calibrating.</description>
+ </entry>
+ <entry value="512" name="GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER">
+ <description>Gimbal device is not assigned to a gimbal manager.</description>
+ </entry>
</enum>
<!-- UAVCAN node health enumeration -->
<enum name="UAVCAN_NODE_HEALTH">
@@ -6471,25 +6495,41 @@
<description>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.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
- <field type="uint16_t" name="flags" enum="GIMBAL_DEVICE_FLAGS">Low level gimbal flags.</field>
+ <field type="uint32_t" name="flags" enum="GIMBAL_DEVICE_FLAGS">Low level gimbal flags.</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, set all fields to NaN if only angular velocity should be used)</field>
<field type="float" name="angular_velocity_x" units="rad/s">X component of angular velocity, positive is banking to the right, NaN to be ignored.</field>
<field type="float" name="angular_velocity_y" units="rad/s">Y component of angular velocity, positive is tilting up, NaN to be ignored.</field>
<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="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 3ec4ef6

Please sign in to comment.