Commit be992336 authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/8bfccff9fe2eda10927eba4ee18bef7d47812f4f
parent 828cbb3b
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -9786,7 +9786,7 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_ ...@@ -9786,7 +9786,7 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i; uint16_t i;
mavlink_gimbal_device_attitude_status_t packet_in = { mavlink_gimbal_device_attitude_status_t packet_in = {
963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,963499128,19107 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,963499128,19107,247,58
}; };
mavlink_gimbal_device_attitude_status_t packet1, packet2; mavlink_gimbal_device_attitude_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1)); memset(&packet1, 0, sizeof(packet1));
...@@ -9796,6 +9796,8 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_ ...@@ -9796,6 +9796,8 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_
packet1.angular_velocity_z = packet_in.angular_velocity_z; packet1.angular_velocity_z = packet_in.angular_velocity_z;
packet1.failure_flags = packet_in.failure_flags; packet1.failure_flags = packet_in.failure_flags;
packet1.flags = packet_in.flags; packet1.flags = packet_in.flags;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
...@@ -9811,12 +9813,12 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_ ...@@ -9811,12 +9813,12 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_device_attitude_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags ); mavlink_msg_gimbal_device_attitude_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags );
mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2); mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_device_attitude_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags ); mavlink_msg_gimbal_device_attitude_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags );
mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2); mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
...@@ -9829,7 +9831,7 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_ ...@@ -9829,7 +9831,7 @@ static void mavlink_test_gimbal_device_attitude_status(uint8_t system_id, uint8_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2)); memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_device_attitude_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags ); mavlink_msg_gimbal_device_attitude_status_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags );
mavlink_msg_gimbal_device_attitude_status_decode(last_msg, &packet2); mavlink_msg_gimbal_device_attitude_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
......
This diff is collapsed.
...@@ -6379,6 +6379,8 @@ ...@@ -6379,6 +6379,8 @@
<wip/> <wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. --> <!-- 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 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>
<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="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="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[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>
......
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment