Commit 62abc603 authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/17207917a38ad690b3995e168b51bf232094b165
parent 1b0dc473
This diff is collapsed.
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
This diff is collapsed.
......@@ -9835,6 +9835,73 @@ static void mavlink_test_obstacle_distance(uint8_t system_id, uint8_t component_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_odometry(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ODOMETRY >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_odometry_t packet_in = {
17.0,45.0,73.0,{ 101.0, 102.0, 103.0, 104.0 },213.0,241.0,269.0,297.0,325.0,353.0,{ 381.0, 382.0, 383.0, 384.0, 385.0, 386.0, 387.0, 388.0, 389.0, 390.0, 391.0, 392.0, 393.0, 394.0, 395.0, 396.0, 397.0, 398.0, 399.0, 400.0, 401.0 },{ 969.0, 970.0, 971.0, 972.0, 973.0, 974.0, 975.0, 976.0, 977.0, 978.0, 979.0, 980.0, 981.0, 982.0, 983.0, 984.0, 985.0, 986.0, 987.0, 988.0, 989.0 },153,220
};
mavlink_odometry_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
packet1.rollspeed = packet_in.rollspeed;
packet1.pitchspeed = packet_in.pitchspeed;
packet1.yawspeed = packet_in.yawspeed;
packet1.frame_id = packet_in.frame_id;
packet1.child_frame_id = packet_in.child_frame_id;
mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
mav_array_memcpy(packet1.pose_covariance, packet_in.pose_covariance, sizeof(float)*21);
mav_array_memcpy(packet1.twist_covariance, packet_in.twist_covariance, sizeof(float)*21);
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_ODOMETRY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ODOMETRY_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_odometry_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_odometry_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_odometry_pack(system_id, component_id, &msg , packet1.frame_id , packet1.child_frame_id , packet1.x , packet1.y , packet1.z , packet1.q , packet1.vx , packet1.vy , packet1.vz , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.pose_covariance , packet1.twist_covariance );
mavlink_msg_odometry_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_odometry_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.frame_id , packet1.child_frame_id , packet1.x , packet1.y , packet1.z , packet1.q , packet1.vx , packet1.vy , packet1.vz , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.pose_covariance , packet1.twist_covariance );
mavlink_msg_odometry_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_odometry_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_odometry_send(MAVLINK_COMM_1 , packet1.frame_id , packet1.child_frame_id , packet1.x , packet1.y , packet1.z , packet1.q , packet1.vx , packet1.vy , packet1.vz , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.pose_covariance , packet1.twist_covariance );
mavlink_msg_odometry_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_heartbeat(system_id, component_id, last_msg);
......@@ -9999,6 +10066,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_param_ext_set(system_id, component_id, last_msg);
mavlink_test_param_ext_ack(system_id, component_id, last_msg);
mavlink_test_obstacle_distance(system_id, component_id, last_msg);
mavlink_test_odometry(system_id, component_id, last_msg);
}
#ifdef __cplusplus
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -601,6 +601,30 @@
<entry value="11" name="MAV_FRAME_GLOBAL_TERRAIN_ALT_INT">
<description>Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.</description>
</entry>
<entry value="12" name="MAV_FRAME_BODY_FRD">
<description>Body fixed frame of reference, Z-down (x: forward, y: right, z: down).</description>
</entry>
<entry value="13" name="MAV_FRAME_BODY_FLU">
<description>Body fixed frame of reference, Z-up (x: forward, y: left, z: up).</description>
</entry>
<entry value="14" name="MAV_FRAME_MOCAP_NED">
<description>Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down).</description>
</entry>
<entry value="15" name="MAV_FRAME_MOCAP_ENU">
<description>Odometry local coordinate frame of data given by a motion capture system, Z-up (x: east, y: north, z: up).</description>
</entry>
<entry value="16" name="MAV_FRAME_VISION_NED">
<description>Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down).</description>
</entry>
<entry value="17" name="MAV_FRAME_VISION_ENU">
<description>Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: east, y: north, z: up).</description>
</entry>
<entry value="18" name="MAV_FRAME_ESTIM_NED">
<description>Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down).</description>
</entry>
<entry value="19" name="MAV_FRAME_ESTIM_ENU">
<description>Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: east, y: noth, z: up).</description>
</entry>
</enum>
<enum name="MAVLINK_DATA_STREAM_TYPE">
<entry name="MAVLINK_DATA_STREAM_IMG_JPEG">
......@@ -4572,5 +4596,22 @@
<field type="uint16_t" name="min_distance" units="cm">Minimum distance the sensor can measure in centimeters.</field>
<field type="uint16_t" name="max_distance" units="cm">Maximum distance the sensor can measure in centimeters.</field>
</message>
<message id="331" name="ODOMETRY">
<description>Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html).</description>
<field type="uint8_t" name="frame_id" enum="MAV_FRAME">Coordinate frame of reference for the pose data, as defined by MAV_FRAME enum.</field>
<field type="uint8_t" name="child_frame_id" enum="MAV_FRAME">Coordinate frame of reference for the velocity in free space (twist) data, as defined by MAV_FRAME enum.</field>
<field type="float" name="x" units="m">X Position</field>
<field type="float" name="y" units="m">Y Position</field>
<field type="float" name="z" units="m">Z Position</field>
<field type="float[4]" name="q">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)</field>
<field type="float" name="vx" units="m/s">X linear speed</field>
<field type="float" name="vy" units="m/s">Y linear speed</field>
<field type="float" name="vz" units="m/s">Z linear speed</field>
<field type="float" name="rollspeed" units="rad/s">Roll angular speed</field>
<field type="float" name="pitchspeed" units="rad/s">Pitch angular speed</field>
<field type="float" name="yawspeed" units="rad/s">Yaw angular speed</field>
<field type="float[21]" name="pose_covariance">Pose (states: x, y, z, roll, pitch, yaw) covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.)</field>
<field type="float[21]" name="twist_covariance">Twist (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed) covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.)</field>
</message>
</messages>
</mavlink>
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 179
......
......@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Mar 23 2018"
#define MAVLINK_BUILD_DATE "Mon Mar 26 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
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