Mavlink update

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1630 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
mich146@hotmail.com 2011-02-11 11:04:52 +00:00
parent 69204d00dc
commit 89eaff17bc
26 changed files with 1715 additions and 656 deletions

View File

@ -1,13 +1,16 @@
table.sortable {
spacing: 5px;
border: 1px solid #656575;
width: 90%;
width: 100%;
}
table.sortable th {
margin: 5px;
}
tr:nth-child(odd) { background-color:#eee; }
tr:nth-child(even) { background-color:#fff; }
table.sortable thead {
background-color:#eee;
color:#666666;
@ -16,13 +19,21 @@ table.sortable thead {
}
table.sortable td {
margin: 5px;
margin: 5px 5px 20px 5px;
vertical-align: top;
}
table.sortable td.mavlink_name {
color:#226633;
font-weight: bold;
width: 25%;
vertical-align: top;
}
table.sortable td.mavlink_mission_param {
color:#334455;
font-weight: bold;
width: 25%;
}
table.sortable td.mavlink_type {

View File

@ -37,8 +37,8 @@
<xsl:template match="//field">
<tr class="mavlink_field">
<td class="mavlink_name"><xsl:value-of select="@name" /></td>
<td class="mavlink_type"><xsl:value-of select="@type" /></td>
<td class="mavlink_name" valign="top"><xsl:value-of select="@name" /></td>
<td class="mavlink_type" valign="top"><xsl:value-of select="@type" /></td>
<td class="mavlink_comment"><xsl:value-of select="." /></td>
</tr>
</xsl:template>
@ -55,7 +55,9 @@
<table class="sortable">
<thead>
<tr>
<th class="mavlink_field_header">CMD ID</th>
<th class="mavlink_field_header">Field Name</th>
<th class="mavlink_field_header">Description</th>
</tr>
</thead>
<tbody>
@ -66,7 +68,24 @@
<xsl:template match="//entry">
<tr class="mavlink_field">
<td class="mavlink_name"><xsl:value-of select="@name" /></td>
<td class="mavlink_type" valign="top"><xsl:value-of select="@value" /></td>
<td class="mavlink_name" valign="top"><xsl:value-of select="@name" /></td>
<td class="mavlink_comment"><xsl:value-of select="description" /></td>
</tr>
<tr>
<td></td>
<xsl:apply-templates select="param" />
</tr>
<tr>
<td colspan="3"><br /></td>
</tr>
</xsl:template>
<xsl:template match="//param">
<tr>
<td></td>
<td class="mavlink_mission_param" valign="top">Mission Param #<xsl:value-of select="@index" /></td>
<td class="mavlink_comment"><xsl:value-of select="." /></td>
</tr>
</xsl:template>

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 8 2011, 09:45 UTC
* Generated on Friday, February 11 2011, 07:42 UTC
*/
#ifndef COMMON_H
#define COMMON_H
@ -18,20 +18,61 @@ extern "C" {
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 1
#define MAVLINK_VERSION 2
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 1
#define MAVLINK_VERSION 2
#endif
// ENUM DEFINITIONS
/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. */
enum MAV_CMD
{
MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint.Hold time (ignored by fixed wing, time to stay at waypoint for rotary wing)Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)0 to pass through the WP, if > 0 radius to pass by WP. Allows trajectory control.Desired yaw angleLatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of timeEmptyEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turnsTurnsEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X secondsSeconds (decimal)EmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch locationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_NAV_LAND=21, /* Land at locationEmptyEmptyEmptyDesired yaw angle.LatitudeLongitudeAltitude*/
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / handMinimum pitch (if airspeed sensor present), desired pitch without sensorEmptyEmptyYaw angle (if magnetometer present), ignored without magnetometerLatitudeLongitudeAltitude*/
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine.Delay in seconds (decimal)EmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached.Descent / Ascend rate (m/s)EmptyEmptyEmptyEmptyEmptyFinish Altitude*/
MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point.Distance (meters)EmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_MODE=176, /* Set system mode.Mode, as defined by ENUM MAV_MODEEmptyEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of timesSequence numberRepeat countEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points.Speed type (0=Airspeed, 1=Ground Speed)Speed (m/s, -1 indicates no change)Throttle ( Percent, -1 indicates no change)EmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location.Use current (1=use current location, 0=use specified location)EmptyEmptyEmptyLatitudeLongitudeAltitude*/
MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.Parameter numberParameter valueEmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition.Relay numberSetting (1=on, 0=off, others possible depending on system hardware)EmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period.Relay numberCycle countCycle time (seconds, decimal)EmptyEmptyEmptyEmpty*/
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value.Servo numberPWM (microseconds, 1000 to 2000 typical)EmptyEmptyEmptyEmptyEmpty*/
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cyles with a desired period.Servo numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/
MAV_CMD_ENUM_END
};
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */
enum MAV_DATA_STREAM
{
MAV_DATA_STREAM_ALL=0, /* Enable all data streams*/
MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.*/
MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS*/
MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW*/
MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.*/
MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.*/
MAV_DATA_STREAM_EXTRA1=250, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA2=251, /* Dependent on the autopilot*/
MAV_DATA_STREAM_EXTRA3=252, /* Dependent on the autopilot*/
MAV_DATA_STREAM_ENUM_END
};
// MESSAGE DEFINITIONS
#include "./mavlink_msg_airspeed.h"
#include "./mavlink_msg_heartbeat.h"
#include "./mavlink_msg_boot.h"
#include "./mavlink_msg_system_time.h"
@ -45,13 +86,15 @@ extern "C" {
#include "./mavlink_msg_param_request_list.h"
#include "./mavlink_msg_param_value.h"
#include "./mavlink_msg_param_set.h"
#include "./mavlink_msg_gps_raw_int.h"
#include "./mavlink_msg_scaled_imu.h"
#include "./mavlink_msg_gps_status.h"
#include "./mavlink_msg_raw_imu.h"
#include "./mavlink_msg_raw_pressure.h"
#include "./mavlink_msg_attitude.h"
#include "./mavlink_msg_local_position.h"
#include "./mavlink_msg_gps_raw.h"
#include "./mavlink_msg_gps_status.h"
#include "./mavlink_msg_global_position.h"
#include "./mavlink_msg_gps_raw.h"
#include "./mavlink_msg_sys_status.h"
#include "./mavlink_msg_rc_channels_raw.h"
#include "./mavlink_msg_rc_channels_scaled.h"
@ -65,7 +108,8 @@ extern "C" {
#include "./mavlink_msg_waypoint_clear_all.h"
#include "./mavlink_msg_waypoint_reached.h"
#include "./mavlink_msg_waypoint_ack.h"
#include "./mavlink_msg_waypoint_set_global_reference.h"
#include "./mavlink_msg_gps_set_global_origin.h"
#include "./mavlink_msg_gps_local_origin_set.h"
#include "./mavlink_msg_local_position_setpoint_set.h"
#include "./mavlink_msg_local_position_setpoint.h"
#include "./mavlink_msg_control_status.h"
@ -79,7 +123,6 @@ extern "C" {
#include "./mavlink_msg_set_altitude.h"
#include "./mavlink_msg_request_data_stream.h"
#include "./mavlink_msg_manual_control.h"
#include "./mavlink_msg_gps_local_origin_set.h"
#include "./mavlink_msg_global_position_int.h"
#include "./mavlink_msg_vfr_hud.h"
#include "./mavlink_msg_debug_vect.h"

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 8 2011, 09:45 UTC
* Generated on Friday, February 11 2011, 07:42 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -1,106 +0,0 @@
// MESSAGE AIRSPEED PACKING
#define MAVLINK_MSG_ID_AIRSPEED 72
typedef struct __mavlink_airspeed_t
{
float airspeed; ///< meters/second
} mavlink_airspeed_t;
/**
* @brief Pack a airspeed message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airspeed meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airspeed)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
i += put_float_by_index(airspeed, i, msg->payload); // meters/second
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a airspeed message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airspeed meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
i += put_float_by_index(airspeed, i, msg->payload); // meters/second
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a airspeed struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param airspeed C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_airspeed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_t* airspeed)
{
return mavlink_msg_airspeed_pack(system_id, component_id, msg, airspeed->airspeed);
}
/**
* @brief Send a airspeed message
* @param chan MAVLink channel to send the message
*
* @param airspeed meters/second
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_airspeed_send(mavlink_channel_t chan, float airspeed)
{
mavlink_message_t msg;
mavlink_msg_airspeed_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airspeed);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE AIRSPEED UNPACKING
/**
* @brief Get field airspeed from airspeed message
*
* @return meters/second
*/
static inline float mavlink_msg_airspeed_get_airspeed(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Decode a airspeed message into a struct
*
* @param msg The message to decode
* @param airspeed C-struct to decode the message contents into
*/
static inline void mavlink_msg_airspeed_decode(const mavlink_message_t* msg, mavlink_airspeed_t* airspeed)
{
airspeed->airspeed = mavlink_msg_airspeed_get_airspeed(msg);
}

View File

@ -4,7 +4,7 @@
typedef struct __mavlink_attitude_t
{
uint64_t usec; ///< Timestamp (microseconds)
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
@ -22,7 +22,7 @@ typedef struct __mavlink_attitude_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
@ -36,7 +36,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
@ -53,7 +53,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
@ -118,7 +118,7 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t us
/**
* @brief Get field usec from attitude message
*
* @return Timestamp (microseconds)
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_attitude_get_usec(const mavlink_message_t* msg)
{

View File

@ -6,7 +6,7 @@ typedef struct __mavlink_global_position_int_t
{
int32_t lat; ///< Latitude / X Position, expressed as * 1E7
int32_t lon; ///< Longitude / Y Position, expressed as * 1E7
int32_t alt; ///< Altitude / negative Z Position, expressed as * 1000
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
@ -23,7 +23,7 @@ typedef struct __mavlink_global_position_int_t
*
* @param lat Latitude / X Position, expressed as * 1E7
* @param lon Longitude / Y Position, expressed as * 1E7
* @param alt Altitude / negative Z Position, expressed as * 1000
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
@ -36,7 +36,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude / X Position, expressed as * 1E7
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude / Y Position, expressed as * 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude / negative Z Position, expressed as * 1000
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
@ -52,7 +52,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param msg The MAVLink message to compress the data into
* @param lat Latitude / X Position, expressed as * 1E7
* @param lon Longitude / Y Position, expressed as * 1E7
* @param alt Altitude / negative Z Position, expressed as * 1000
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
@ -65,7 +65,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude / X Position, expressed as * 1E7
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude / Y Position, expressed as * 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude / negative Z Position, expressed as * 1000
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters)
i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100
i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100
i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100
@ -92,7 +92,7 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id,
*
* @param lat Latitude / X Position, expressed as * 1E7
* @param lon Longitude / Y Position, expressed as * 1E7
* @param alt Altitude / negative Z Position, expressed as * 1000
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
@ -142,7 +142,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude / negative Z Position, expressed as * 1000
* @return Altitude in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{

View File

@ -1,6 +1,6 @@
// MESSAGE GPS_LOCAL_ORIGIN_SET PACKING
#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET 71
#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET 49
typedef struct __mavlink_gps_local_origin_set_t
{

View File

@ -4,7 +4,7 @@
typedef struct __mavlink_gps_raw_t
{
uint64_t usec; ///< Timestamp (microseconds since unix epoch)
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix
float lat; ///< Latitude in degrees
float lon; ///< Longitude in degrees
@ -24,7 +24,7 @@ typedef struct __mavlink_gps_raw_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since unix epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat Latitude in degrees
* @param lon Longitude in degrees
@ -40,7 +40,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since unix epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat Latitude in degrees
* @param lon Longitude in degrees
@ -75,7 +75,7 @@ static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t com
* @brief Send a gps_raw message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat Latitude in degrees
* @param lon Longitude in degrees
@ -130,7 +130,7 @@ static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t use
/**
* @brief Get field usec from gps_raw message
*
* @return Timestamp (microseconds since unix epoch)
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
{

View File

@ -0,0 +1,281 @@
// MESSAGE GPS_RAW_INT PACKING
#define MAVLINK_MSG_ID_GPS_RAW_INT 25
typedef struct __mavlink_gps_raw_int_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix
int32_t lat; ///< Latitude in 1E7 degrees
int32_t lon; ///< Longitude in 1E7 degrees
int32_t alt; ///< Altitude in 1E3 meters (millimeters)
float eph; ///< GPS HDOP
float epv; ///< GPS VDOP
float v; ///< GPS ground speed (m/s)
float hdg; ///< Compass heading in degrees, 0..360 degrees
} mavlink_gps_raw_int_t;
/**
* @brief Pack a gps_raw_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters)
i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
i += put_float_by_index(v, i, msg->payload); // GPS ground speed (m/s)
i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a gps_raw_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters)
i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
i += put_float_by_index(v, i, msg->payload); // GPS ground speed (m/s)
i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a gps_raw_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_raw_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->v, gps_raw_int->hdg);
}
/**
* @brief Send a gps_raw_int message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
{
mavlink_message_t msg;
mavlink_msg_gps_raw_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE GPS_RAW_INT UNPACKING
/**
* @brief Get field usec from gps_raw_int message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_gps_raw_int_get_usec(const mavlink_message_t* msg)
{
generic_64bit r;
r.b[7] = (msg->payload)[0];
r.b[6] = (msg->payload)[1];
r.b[5] = (msg->payload)[2];
r.b[4] = (msg->payload)[3];
r.b[3] = (msg->payload)[4];
r.b[2] = (msg->payload)[5];
r.b[1] = (msg->payload)[6];
r.b[0] = (msg->payload)[7];
return (uint64_t)r.ll;
}
/**
* @brief Get field fix_type from gps_raw_int message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
}
/**
* @brief Get field lat from gps_raw_int message
*
* @return Latitude in 1E7 degrees
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field lon from gps_raw_int message
*
* @return Longitude in 1E7 degrees
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field alt from gps_raw_int message
*
* @return Altitude in 1E3 meters (millimeters)
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field eph from gps_raw_int message
*
* @return GPS HDOP
*/
static inline float mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[3];
return (float)r.f;
}
/**
* @brief Get field epv from gps_raw_int message
*
* @return GPS VDOP
*/
static inline float mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field v from gps_raw_int message
*
* @return GPS ground speed (m/s)
*/
static inline float mavlink_msg_gps_raw_int_get_v(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field hdg from gps_raw_int message
*
* @return Compass heading in degrees, 0..360 degrees
*/
static inline float mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a gps_raw_int message into a struct
*
* @param msg The message to decode
* @param gps_raw_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
{
gps_raw_int->usec = mavlink_msg_gps_raw_int_get_usec(msg);
gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
gps_raw_int->v = mavlink_msg_gps_raw_int_get_v(msg);
gps_raw_int->hdg = mavlink_msg_gps_raw_int_get_hdg(msg);
}

View File

@ -0,0 +1,250 @@
// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48
typedef struct __mavlink_gps_set_global_origin_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint32_t global_x; ///< global x position * 1E7
uint32_t global_y; ///< global y position * 1E7
uint32_t global_z; ///< global z position * 1000
float local_x; ///< local x position that matches the global x position
float local_y; ///< local y position that matches the global y position
float local_z; ///< local z position that matches the global z position
} mavlink_gps_set_global_origin_t;
/**
* @brief Pack a gps_set_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param global_x global x position * 1E7
* @param global_y global y position * 1E7
* @param global_z global z position * 1000
* @param local_x local x position that matches the global x position
* @param local_y local y position that matches the global y position
* @param local_z local z position that matches the global z position
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t global_x, uint32_t global_y, uint32_t global_z, float local_x, float local_y, float local_z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint32_t_by_index(global_x, i, msg->payload); // global x position * 1E7
i += put_uint32_t_by_index(global_y, i, msg->payload); // global y position * 1E7
i += put_uint32_t_by_index(global_z, i, msg->payload); // global z position * 1000
i += put_float_by_index(local_x, i, msg->payload); // local x position that matches the global x position
i += put_float_by_index(local_y, i, msg->payload); // local y position that matches the global y position
i += put_float_by_index(local_z, i, msg->payload); // local z position that matches the global z position
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a gps_set_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param global_x global x position * 1E7
* @param global_y global y position * 1E7
* @param global_z global z position * 1000
* @param local_x local x position that matches the global x position
* @param local_y local y position that matches the global y position
* @param local_z local z position that matches the global z position
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t global_x, uint32_t global_y, uint32_t global_z, float local_x, float local_y, float local_z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint32_t_by_index(global_x, i, msg->payload); // global x position * 1E7
i += put_uint32_t_by_index(global_y, i, msg->payload); // global y position * 1E7
i += put_uint32_t_by_index(global_z, i, msg->payload); // global z position * 1000
i += put_float_by_index(local_x, i, msg->payload); // local x position that matches the global x position
i += put_float_by_index(local_y, i, msg->payload); // local y position that matches the global y position
i += put_float_by_index(local_z, i, msg->payload); // local z position that matches the global z position
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a gps_set_global_origin struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_set_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->global_x, gps_set_global_origin->global_y, gps_set_global_origin->global_z, gps_set_global_origin->local_x, gps_set_global_origin->local_y, gps_set_global_origin->local_z);
}
/**
* @brief Send a gps_set_global_origin message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param global_x global x position * 1E7
* @param global_y global y position * 1E7
* @param global_z global z position * 1000
* @param local_x local x position that matches the global x position
* @param local_y local y position that matches the global y position
* @param local_z local z position that matches the global z position
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t global_x, uint32_t global_y, uint32_t global_z, float local_x, float local_y, float local_z)
{
mavlink_message_t msg;
mavlink_msg_gps_set_global_origin_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, global_x, global_y, global_z, local_x, local_y, local_z);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING
/**
* @brief Get field target_system from gps_set_global_origin message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from gps_set_global_origin message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field global_x from gps_set_global_origin message
*
* @return global x position * 1E7
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_global_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
return (uint32_t)r.i;
}
/**
* @brief Get field global_y from gps_set_global_origin message
*
* @return global y position * 1E7
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_global_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[3];
return (uint32_t)r.i;
}
/**
* @brief Get field global_z from gps_set_global_origin message
*
* @return global z position * 1000
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_global_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3];
return (uint32_t)r.i;
}
/**
* @brief Get field local_x from gps_set_global_origin message
*
* @return local x position that matches the global x position
*/
static inline float mavlink_msg_gps_set_global_origin_get_local_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t))[3];
return (float)r.f;
}
/**
* @brief Get field local_y from gps_set_global_origin message
*
* @return local y position that matches the global y position
*/
static inline float mavlink_msg_gps_set_global_origin_get_local_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field local_z from gps_set_global_origin message
*
* @return local z position that matches the global z position
*/
static inline float mavlink_msg_gps_set_global_origin_get_local_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a gps_set_global_origin message into a struct
*
* @param msg The message to decode
* @param gps_set_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg);
gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg);
gps_set_global_origin->global_x = mavlink_msg_gps_set_global_origin_get_global_x(msg);
gps_set_global_origin->global_y = mavlink_msg_gps_set_global_origin_get_global_y(msg);
gps_set_global_origin->global_z = mavlink_msg_gps_set_global_origin_get_global_z(msg);
gps_set_global_origin->local_x = mavlink_msg_gps_set_global_origin_get_local_x(msg);
gps_set_global_origin->local_y = mavlink_msg_gps_set_global_origin_get_local_y(msg);
gps_set_global_origin->local_z = mavlink_msg_gps_set_global_origin_get_local_z(msg);
}

View File

@ -29,7 +29,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(1, i, msg->payload); // MAVLink version
i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -51,7 +51,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_
i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(1, i, msg->payload); // MAVLink version
i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}

View File

@ -4,7 +4,7 @@
typedef struct __mavlink_local_position_t
{
uint64_t usec; ///< Timestamp (microseconds since unix epoch)
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float x; ///< X Position
float y; ///< Y Position
float z; ///< Z Position
@ -22,7 +22,7 @@ typedef struct __mavlink_local_position_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since unix epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
@ -36,7 +36,7 @@ static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(x, i, msg->payload); // X Position
i += put_float_by_index(y, i, msg->payload); // Y Position
i += put_float_by_index(z, i, msg->payload); // Z Position
@ -53,7 +53,7 @@ static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since unix epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, u
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(x, i, msg->payload); // X Position
i += put_float_by_index(y, i, msg->payload); // Y Position
i += put_float_by_index(z, i, msg->payload); // Z Position
@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint
* @brief Send a local_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
@ -118,7 +118,7 @@ static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint6
/**
* @brief Get field usec from local_position message
*
* @return Timestamp (microseconds since unix epoch)
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_local_position_get_usec(const mavlink_message_t* msg)
{

View File

@ -4,10 +4,10 @@
typedef struct __mavlink_local_position_setpoint_t
{
float x; ///< x position 1
float y; ///< y position 1
float z; ///< z position 1
float yaw; ///< x position 2
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
} mavlink_local_position_setpoint_t;
@ -19,10 +19,10 @@ typedef struct __mavlink_local_position_setpoint_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw)
@ -30,10 +30,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -44,10 +44,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
@ -55,10 +55,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -80,10 +80,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system
* @brief Send a local_position_setpoint message
* @param chan MAVLink channel to send the message
*
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -100,7 +100,7 @@ static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t ch
/**
* @brief Get field x from local_position_setpoint message
*
* @return x position 1
* @return x position
*/
static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg)
{
@ -115,7 +115,7 @@ static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_mess
/**
* @brief Get field y from local_position_setpoint message
*
* @return y position 1
* @return y position
*/
static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg)
{
@ -130,7 +130,7 @@ static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_mess
/**
* @brief Get field z from local_position_setpoint message
*
* @return z position 1
* @return z position
*/
static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg)
{
@ -145,7 +145,7 @@ static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_mess
/**
* @brief Get field yaw from local_position_setpoint message
*
* @return x position 2
* @return Desired yaw angle
*/
static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
{

View File

@ -6,10 +6,10 @@ typedef struct __mavlink_local_position_setpoint_set_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
float x; ///< x position 1
float y; ///< y position 1
float z; ///< z position 1
float yaw; ///< x position 2
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
} mavlink_local_position_setpoint_set_t;
@ -23,10 +23,10 @@ typedef struct __mavlink_local_position_setpoint_set_t
*
* @param target_system System ID
* @param target_component Component ID
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
@ -36,10 +36,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t syst
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -52,10 +52,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t syst
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
@ -65,10 +65,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack_chan(uint8_t
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -92,10 +92,10 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t sy
*
* @param target_system System ID
* @param target_component Component ID
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -132,7 +132,7 @@ static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_compone
/**
* @brief Get field x from local_position_setpoint_set message
*
* @return x position 1
* @return x position
*/
static inline float mavlink_msg_local_position_setpoint_set_get_x(const mavlink_message_t* msg)
{
@ -147,7 +147,7 @@ static inline float mavlink_msg_local_position_setpoint_set_get_x(const mavlink_
/**
* @brief Get field y from local_position_setpoint_set message
*
* @return y position 1
* @return y position
*/
static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_message_t* msg)
{
@ -162,7 +162,7 @@ static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_
/**
* @brief Get field z from local_position_setpoint_set message
*
* @return z position 1
* @return z position
*/
static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_message_t* msg)
{
@ -177,7 +177,7 @@ static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_
/**
* @brief Get field yaw from local_position_setpoint_set message
*
* @return x position 2
* @return Desired yaw angle
*/
static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlink_message_t* msg)
{

View File

@ -11,6 +11,7 @@ typedef struct __mavlink_nav_controller_output_t
uint16_t wp_dist; ///< Distance to active waypoint in meters
float alt_error; ///< Current altitude error in meters
float aspd_error; ///< Current airspeed error in meters/second
float xtrack_error; ///< Current crosstrack error on x-y plane in meters
} mavlink_nav_controller_output_t;
@ -29,9 +30,10 @@ typedef struct __mavlink_nav_controller_output_t
* @param wp_dist Distance to active waypoint in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error)
static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
@ -43,6 +45,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id,
i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters
i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters
i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second
i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -60,9 +63,10 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id,
* @param wp_dist Distance to active waypoint in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error)
static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
@ -74,6 +78,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste
i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters
i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters
i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second
i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -88,7 +93,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste
*/
static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
{
return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error);
return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
}
/**
@ -102,13 +107,14 @@ static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_i
* @param wp_dist Distance to active waypoint in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error)
static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
mavlink_message_t msg;
mavlink_msg_nav_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error);
mavlink_msg_nav_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error);
mavlink_send_uart(chan, &msg);
}
@ -214,6 +220,21 @@ static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavli
return (float)r.f;
}
/**
* @brief Get field xtrack_error from nav_controller_output message
*
* @return Current crosstrack error on x-y plane in meters
*/
static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a nav_controller_output message into a struct
*
@ -229,4 +250,5 @@ static inline void mavlink_msg_nav_controller_output_decode(const mavlink_messag
nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg);
nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg);
nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg);
nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg);
}

View File

@ -4,16 +4,16 @@
typedef struct __mavlink_raw_imu_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch)
int16_t xacc; ///< X acceleration (mg raw)
int16_t yacc; ///< Y acceleration (mg raw)
int16_t zacc; ///< Z acceleration (mg raw)
int16_t xgyro; ///< Angular speed around X axis (millirad /sec)
int16_t ygyro; ///< Angular speed around Y axis (millirad /sec)
int16_t zgyro; ///< Angular speed around Z axis (millirad /sec)
int16_t xmag; ///< X Magnetic field (milli tesla)
int16_t ymag; ///< Y Magnetic field (milli tesla)
int16_t zmag; ///< Z Magnetic field (milli tesla)
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t xacc; ///< X acceleration (raw)
int16_t yacc; ///< Y acceleration (raw)
int16_t zacc; ///< Z acceleration (raw)
int16_t xgyro; ///< Angular speed around X axis (raw)
int16_t ygyro; ///< Angular speed around Y axis (raw)
int16_t zgyro; ///< Angular speed around Z axis (raw)
int16_t xmag; ///< X Magnetic field (raw)
int16_t ymag; ///< Y Magnetic field (raw)
int16_t zmag; ///< Z Magnetic field (raw)
} mavlink_raw_imu_t;
@ -25,16 +25,16 @@ typedef struct __mavlink_raw_imu_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch)
* @param xacc X acceleration (mg raw)
* @param yacc Y acceleration (mg raw)
* @param zacc Z acceleration (mg raw)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
@ -42,16 +42,16 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg raw)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg raw)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (raw)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (raw)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (raw)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (raw)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (raw)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (raw)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (raw)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (raw)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -62,16 +62,16 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch)
* @param xacc X acceleration (mg raw)
* @param yacc Y acceleration (mg raw)
* @param zacc Z acceleration (mg raw)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
@ -79,16 +79,16 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg raw)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg raw)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (raw)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (raw)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (raw)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (raw)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (raw)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (raw)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (raw)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (raw)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -110,16 +110,16 @@ static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t com
* @brief Send a raw_imu message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch)
* @param xacc X acceleration (mg raw)
* @param yacc Y acceleration (mg raw)
* @param zacc Z acceleration (mg raw)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@ -136,7 +136,7 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t use
/**
* @brief Get field usec from raw_imu message
*
* @return Timestamp (microseconds since UNIX epoch)
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_raw_imu_get_usec(const mavlink_message_t* msg)
{
@ -155,7 +155,7 @@ static inline uint64_t mavlink_msg_raw_imu_get_usec(const mavlink_message_t* msg
/**
* @brief Get field xacc from raw_imu message
*
* @return X acceleration (mg raw)
* @return X acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg)
{
@ -168,7 +168,7 @@ static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg)
/**
* @brief Get field yacc from raw_imu message
*
* @return Y acceleration (mg raw)
* @return Y acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg)
{
@ -181,7 +181,7 @@ static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg)
/**
* @brief Get field zacc from raw_imu message
*
* @return Z acceleration (mg raw)
* @return Z acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg)
{
@ -194,7 +194,7 @@ static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg)
/**
* @brief Get field xgyro from raw_imu message
*
* @return Angular speed around X axis (millirad /sec)
* @return Angular speed around X axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg)
{
@ -207,7 +207,7 @@ static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg
/**
* @brief Get field ygyro from raw_imu message
*
* @return Angular speed around Y axis (millirad /sec)
* @return Angular speed around Y axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg)
{
@ -220,7 +220,7 @@ static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg
/**
* @brief Get field zgyro from raw_imu message
*
* @return Angular speed around Z axis (millirad /sec)
* @return Angular speed around Z axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg)
{
@ -233,7 +233,7 @@ static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg
/**
* @brief Get field xmag from raw_imu message
*
* @return X Magnetic field (milli tesla)
* @return X Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg)
{
@ -246,7 +246,7 @@ static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg)
/**
* @brief Get field ymag from raw_imu message
*
* @return Y Magnetic field (milli tesla)
* @return Y Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg)
{
@ -259,7 +259,7 @@ static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg)
/**
* @brief Get field zmag from raw_imu message
*
* @return Z Magnetic field (milli tesla)
* @return Z Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg)
{

View File

@ -4,10 +4,10 @@
typedef struct __mavlink_raw_pressure_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch)
uint16_t press_abs; ///< Absolute pressure (hectopascal)
int16_t press_diff1; ///< Differential pressure 1 (hectopascal)
int16_t press_diff2; ///< Differential pressure 2 (hectopascal)
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float press_abs; ///< Absolute pressure (hectopascal)
float press_diff1; ///< Differential pressure 1 (hectopascal)
float press_diff2; ///< Differential pressure 2 (hectopascal)
int16_t temperature; ///< Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
} mavlink_raw_pressure_t;
@ -20,22 +20,22 @@ typedef struct __mavlink_raw_pressure_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_uint16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_float_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_float_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
return mavlink_finalize_message(msg, system_id, component_id, i);
@ -47,22 +47,22 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_uint16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_float_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_float_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
@ -85,7 +85,7 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_
* @brief Send a raw_pressure message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch)
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, uint16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature)
{
mavlink_message_t msg;
mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2, temperature);
@ -106,7 +106,7 @@ static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_
/**
* @brief Get field usec from raw_pressure message
*
* @return Timestamp (microseconds since UNIX epoch)
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t* msg)
{
@ -127,12 +127,14 @@ static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t
*
* @return Absolute pressure (hectopascal)
*/
static inline uint16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
static inline float mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t))[1];
return (uint16_t)r.s;
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t))[3];
return (float)r.f;
}
/**
@ -140,12 +142,14 @@ static inline uint16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_mess
*
* @return Differential pressure 1 (hectopascal)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
static inline float mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t))[1];
return (int16_t)r.s;
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
return (float)r.f;
}
/**
@ -153,12 +157,14 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_mes
*
* @return Differential pressure 2 (hectopascal)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
static inline float mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
@ -169,8 +175,8 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_mes
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
return (int16_t)r.s;
}

View File

@ -0,0 +1,290 @@
// MESSAGE SCALED_IMU PACKING
#define MAVLINK_MSG_ID_SCALED_IMU 26
typedef struct __mavlink_scaled_imu_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t xacc; ///< X acceleration (mg)
int16_t yacc; ///< Y acceleration (mg)
int16_t zacc; ///< Z acceleration (mg)
int16_t xgyro; ///< Angular speed around X axis (millirad /sec)
int16_t ygyro; ///< Angular speed around Y axis (millirad /sec)
int16_t zgyro; ///< Angular speed around Z axis (millirad /sec)
int16_t xmag; ///< X Magnetic field (milli tesla)
int16_t ymag; ///< Y Magnetic field (milli tesla)
int16_t zmag; ///< Z Magnetic field (milli tesla)
} mavlink_scaled_imu_t;
/**
* @brief Pack a scaled_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a scaled_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a scaled_imu struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param scaled_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
{
return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->usec, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
}
/**
* @brief Send a scaled_imu message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
mavlink_message_t msg;
mavlink_msg_scaled_imu_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SCALED_IMU UNPACKING
/**
* @brief Get field usec from scaled_imu message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_scaled_imu_get_usec(const mavlink_message_t* msg)
{
generic_64bit r;
r.b[7] = (msg->payload)[0];
r.b[6] = (msg->payload)[1];
r.b[5] = (msg->payload)[2];
r.b[4] = (msg->payload)[3];
r.b[3] = (msg->payload)[4];
r.b[2] = (msg->payload)[5];
r.b[1] = (msg->payload)[6];
r.b[0] = (msg->payload)[7];
return (uint64_t)r.ll;
}
/**
* @brief Get field xacc from scaled_imu message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field yacc from scaled_imu message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field zacc from scaled_imu message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field xgyro from scaled_imu message
*
* @return Angular speed around X axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field ygyro from scaled_imu message
*
* @return Angular speed around Y axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field zgyro from scaled_imu message
*
* @return Angular speed around Z axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field xmag from scaled_imu message
*
* @return X Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field ymag from scaled_imu message
*
* @return Y Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field zmag from scaled_imu message
*
* @return Z Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Decode a scaled_imu message into a struct
*
* @param msg The message to decode
* @param scaled_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu)
{
scaled_imu->usec = mavlink_msg_scaled_imu_get_usec(msg);
scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg);
scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg);
scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg);
scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg);
scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg);
scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg);
scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg);
scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg);
scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg);
}

View File

@ -6,10 +6,10 @@ typedef struct __mavlink_vfr_hud_t
{
float airspeed; ///< Current airspeed in m/s
float groundspeed; ///< Current ground speed in m/s
int16_t heading; ///< Current heading in degrees
uint16_t alt; ///< Current altitude (MSL), in meters
float climb; ///< Current climb rate in meters/second
int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north)
uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100
float alt; ///< Current altitude (MSL), in meters
float climb; ///< Current climb rate in meters/second
} mavlink_vfr_hud_t;
@ -23,23 +23,23 @@ typedef struct __mavlink_vfr_hud_t
*
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @param throttle Current throttle setting in integer percent, 0 to 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t alt, float climb, uint16_t throttle)
static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
i += put_float_by_index(airspeed, i, msg->payload); // Current airspeed in m/s
i += put_float_by_index(groundspeed, i, msg->payload); // Current ground speed in m/s
i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees
i += put_uint16_t_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters
i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second
i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees, in compass units (0..360, 0=north)
i += put_uint16_t_by_index(throttle, i, msg->payload); // Current throttle setting in integer percent, 0 to 100
i += put_float_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters
i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -52,23 +52,23 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo
* @param msg The MAVLink message to compress the data into
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @param throttle Current throttle setting in integer percent, 0 to 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t alt, float climb, uint16_t throttle)
static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
i += put_float_by_index(airspeed, i, msg->payload); // Current airspeed in m/s
i += put_float_by_index(groundspeed, i, msg->payload); // Current ground speed in m/s
i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees
i += put_uint16_t_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters
i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second
i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees, in compass units (0..360, 0=north)
i += put_uint16_t_by_index(throttle, i, msg->payload); // Current throttle setting in integer percent, 0 to 100
i += put_float_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters
i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -83,7 +83,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud)
{
return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->alt, vfr_hud->climb, vfr_hud->throttle);
return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
}
/**
@ -92,17 +92,17 @@ static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t com
*
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @param throttle Current throttle setting in integer percent, 0 to 100
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t alt, float climb, uint16_t throttle)
static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
mavlink_message_t msg;
mavlink_msg_vfr_hud_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airspeed, groundspeed, heading, alt, climb, throttle);
mavlink_msg_vfr_hud_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airspeed, groundspeed, heading, throttle, alt, climb);
mavlink_send_uart(chan, &msg);
}
@ -142,7 +142,7 @@ static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t*
/**
* @brief Get field heading from vfr_hud message
*
* @return Current heading in degrees
* @return Current heading in degrees, in compass units (0..360, 0=north)
*/
static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
{
@ -153,11 +153,11 @@ static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* m
}
/**
* @brief Get field alt from vfr_hud message
* @brief Get field throttle from vfr_hud message
*
* @return Current altitude (MSL), in meters
* @return Current throttle setting in integer percent, 0 to 100
*/
static inline uint16_t mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[0];
@ -166,11 +166,11 @@ static inline uint16_t mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
}
/**
* @brief Get field climb from vfr_hud message
* @brief Get field alt from vfr_hud message
*
* @return Current climb rate in meters/second
* @return Current altitude (MSL), in meters
*/
static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[0];
@ -181,16 +181,18 @@ static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
}
/**
* @brief Get field throttle from vfr_hud message
* @brief Get field climb from vfr_hud message
*
* @return Current throttle setting in integer percent, 0 to 100
* @return Current climb rate in meters/second
*/
static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1];
return (uint16_t)r.s;
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[3];
return (float)r.f;
}
/**
@ -204,7 +206,7 @@ static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavl
vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg);
vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg);
vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg);
vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
}

View File

@ -8,17 +8,16 @@ typedef struct __mavlink_waypoint_t
uint8_t target_component; ///< Component ID
uint16_t seq; ///< Sequence
uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
uint8_t action; ///< The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
float orbit; ///< Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
uint8_t orbit_direction; ///< Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
float param1; ///< For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
float param2; ///< For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
uint8_t current; ///< false:0, true:1
float x; ///< local: x position, global: longitude
float y; ///< y position: global: latitude
float z; ///< z position: global: altitude
float yaw; ///< yaw orientation in radians, 0 = NORTH
uint8_t autocontinue; ///< autocontinue to next wp
float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
float x; ///< PARAM5 / local: x position, global: longitude
float y; ///< PARAM6 / y position: global: latitude
float z; ///< PARAM7 / z position: global: altitude
} mavlink_waypoint_t;
@ -34,20 +33,19 @@ typedef struct __mavlink_waypoint_t
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param action The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
* @param orbit Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
* @param orbit_direction Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
* @param param1 For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
* @param param2 For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
* @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
* @param current false:0, true:1
* @param x local: x position, global: longitude
* @param y y position: global: latitude
* @param z z position: global: altitude
* @param yaw yaw orientation in radians, 0 = NORTH
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: longitude
* @param y PARAM6 / y position: global: latitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
@ -56,17 +54,16 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
i += put_uint8_t_by_index(action, i, msg->payload); // The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
i += put_float_by_index(orbit, i, msg->payload); // Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); // Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
i += put_float_by_index(param1, i, msg->payload); // For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); // For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
i += put_float_by_index(x, i, msg->payload); // local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); // y position: global: latitude
i += put_float_by_index(z, i, msg->payload); // z position: global: altitude
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: latitude
i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -81,20 +78,19 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param action The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
* @param orbit Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
* @param orbit_direction Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
* @param param1 For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
* @param param2 For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
* @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
* @param current false:0, true:1
* @param x local: x position, global: longitude
* @param y y position: global: latitude
* @param z z position: global: altitude
* @param yaw yaw orientation in radians, 0 = NORTH
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: longitude
* @param y PARAM6 / y position: global: latitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
@ -103,17 +99,16 @@ static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
i += put_uint8_t_by_index(action, i, msg->payload); // The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
i += put_float_by_index(orbit, i, msg->payload); // Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); // Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
i += put_float_by_index(param1, i, msg->payload); // For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); // For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
i += put_float_by_index(x, i, msg->payload); // local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); // y position: global: latitude
i += put_float_by_index(z, i, msg->payload); // z position: global: altitude
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: latitude
i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -128,7 +123,7 @@ static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint)
{
return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->action, waypoint->orbit, waypoint->orbit_direction, waypoint->param1, waypoint->param2, waypoint->current, waypoint->x, waypoint->y, waypoint->z, waypoint->yaw, waypoint->autocontinue);
return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z);
}
/**
@ -139,24 +134,23 @@ static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t co
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param action The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
* @param orbit Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
* @param orbit_direction Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
* @param param1 For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
* @param param2 For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
* @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
* @param current false:0, true:1
* @param x local: x position, global: longitude
* @param y y position: global: latitude
* @param z z position: global: altitude
* @param yaw yaw orientation in radians, 0 = NORTH
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: longitude
* @param y PARAM6 / y position: global: latitude
* @param z PARAM7 / z position: global: altitude
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
mavlink_message_t msg;
mavlink_msg_waypoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq, frame, action, orbit, orbit_direction, param1, param2, current, x, y, z, yaw, autocontinue);
mavlink_msg_waypoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z);
mavlink_send_uart(chan, &msg);
}
@ -207,70 +201,15 @@ static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* ms
}
/**
* @brief Get field action from waypoint message
* @brief Get field command from waypoint message
*
* @return The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
* @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
*/
static inline uint8_t mavlink_msg_waypoint_get_action(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field orbit from waypoint message
*
* @return Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
*/
static inline float mavlink_msg_waypoint_get_orbit(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field orbit_direction from waypoint message
*
* @return Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
*/
static inline uint8_t mavlink_msg_waypoint_get_orbit_direction(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
}
/**
* @brief Get field param1 from waypoint message
*
* @return For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
*/
static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field param2 from waypoint message
*
* @return For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
*/
static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field current from waypoint message
*
@ -278,67 +217,7 @@ static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg
*/
static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
}
/**
* @brief Get field x from waypoint message
*
* @return local: x position, global: longitude
*/
static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field y from waypoint message
*
* @return y position: global: latitude
*/
static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field z from waypoint message
*
* @return z position: global: altitude
*/
static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field yaw from waypoint message
*
* @return yaw orientation in radians, 0 = NORTH
*/
static inline float mavlink_msg_waypoint_get_yaw(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
@ -348,7 +227,112 @@ static inline float mavlink_msg_waypoint_get_yaw(const mavlink_message_t* msg)
*/
static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field param1 from waypoint message
*
* @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
*/
static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field param2 from waypoint message
*
* @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
*/
static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field param3 from waypoint message
*
* @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
*/
static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field param4 from waypoint message
*
* @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
*/
static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field x from waypoint message
*
* @return PARAM5 / local: x position, global: longitude
*/
static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field y from waypoint message
*
* @return PARAM6 / y position: global: latitude
*/
static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field z from waypoint message
*
* @return PARAM7 / z position: global: altitude
*/
static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
@ -363,15 +347,14 @@ static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mav
waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg);
waypoint->seq = mavlink_msg_waypoint_get_seq(msg);
waypoint->frame = mavlink_msg_waypoint_get_frame(msg);
waypoint->action = mavlink_msg_waypoint_get_action(msg);
waypoint->orbit = mavlink_msg_waypoint_get_orbit(msg);
waypoint->orbit_direction = mavlink_msg_waypoint_get_orbit_direction(msg);
waypoint->command = mavlink_msg_waypoint_get_command(msg);
waypoint->current = mavlink_msg_waypoint_get_current(msg);
waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg);
waypoint->param1 = mavlink_msg_waypoint_get_param1(msg);
waypoint->param2 = mavlink_msg_waypoint_get_param2(msg);
waypoint->current = mavlink_msg_waypoint_get_current(msg);
waypoint->param3 = mavlink_msg_waypoint_get_param3(msg);
waypoint->param4 = mavlink_msg_waypoint_get_param4(msg);
waypoint->x = mavlink_msg_waypoint_get_x(msg);
waypoint->y = mavlink_msg_waypoint_get_y(msg);
waypoint->z = mavlink_msg_waypoint_get_z(msg);
waypoint->yaw = mavlink_msg_waypoint_get_yaw(msg);
waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg);
}

View File

@ -112,20 +112,22 @@ enum MAV_AUTOPILOT_TYPE
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3
};
};
enum MAV_COMPONENT {
enum MAV_COMPONENT
{
MAV_COMP_ID_GPS,
MAV_COMP_ID_WAYPOINTPLANNER,
MAV_COMP_ID_BLOBTRACKER,
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
};
};
enum MAV_FRAME
{
@ -134,29 +136,6 @@ enum MAV_FRAME
MAV_FRAME_MISSION = 2
};
enum MAV_DATA_STREAM
{
MAV_DATA_STREAM_ALL = 0,
MAV_DATA_STREAM_RAW_SENSORS = 1,
MAV_DATA_STREAM_EXTENDED_STATUS = 2,
MAV_DATA_STREAM_RC_CHANNELS = 3,
MAV_DATA_STREAM_RAW_CONTROLLER = 4,
MAV_DATA_STREAM_RAW_SENSOR_FUSION = 5,
MAV_DATA_STREAM_POSITION = 6,
MAV_DATA_STREAM_EXTRA1 = 7,
MAV_DATA_STREAM_EXTRA2 = 8,
MAV_DATA_STREAM_EXTRA3 = 9
};
enum DATA_TYPES
{
DATA_TYPE_JPEG_IMAGE = 0,
DATA_TYPE_RAW_IMAGE = 1,
DATA_TYPE_KINECT
};
#define MAVLINK_STX 0x55 ///< Packet start sign
#define MAVLINK_STX_LEN 1 ///< Length of start sign
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 8 2011, 09:45 UTC
* Generated on Friday, February 11 2011, 07:42 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 8 2011, 09:45 UTC
* Generated on Friday, February 11 2011, 07:42 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H
@ -35,7 +35,17 @@ enum SLUGS_PID_INDX_IDS
{
PID_YAW_DAMPER=2,
PID_PITCH=3, /* With comment: PID Pitch parameter*/
PID_ALT_HOLD=50
PID_ALT_HOLD=50,
SLUGS_PID_INDX_IDS_ENUM_END
};
/** @brief Content Types for data transmission handshake */
enum DATA_TYPES
{
DATA_TYPE_JPEG_IMAGE=1,
DATA_TYPE_RAW_IMAGE=2,
DATA_TYPE_KINECT=3,
DATA_TYPES_ENUM_END
};

View File

@ -1,6 +1,242 @@
<?xml version="1.0"?>
<mavlink>
<version>1</version>
<version>2</version>
<enums>
<enum name="MAV_CMD" >
<description>Commands to be executed by the MAV. They can be executed on user request,
or as part of a mission script. If the action is used in a mission, the parameter mapping
to the waypoint/mission message is as follows:
Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7.
</description>
<entry name="MAV_CMD_NAV_WAYPOINT" value="16">
<description>Navigate to waypoint.</description>
<param index="1">Hold time (ignored by fixed wing, time to stay at waypoint for rotary wing)</param>
<param index="2">Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)</param>
<param index="3">0 to pass through the WP, if > 0 radius to pass by WP. Allows trajectory control.</param>
<param index="4">Desired yaw angle</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_LOITER_UNLIM" value="17">
<description>Loiter around this waypoint an unlimited amount of time</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_LOITER_TURNS" value="18">
<description>Loiter around this waypoint for X turns</description>
<param index="1">Turns</param>
<param index="2">Empty</param>
<param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_LOITER_TIME" value="19">
<description>Loiter around this waypoint for X seconds</description>
<param index="1">Seconds (decimal)</param>
<param index="2">Empty</param>
<param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_RETURN_TO_LAUNCH" value="20">
<description>Return to launch location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_NAV_LAND" value="21">
<description>Land at location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_TAKEOFF" value="22">
<description>Takeoff from ground / hand</description>
<param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_LAST" value="95">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_CONDITION_DELAY" value="112">
<description>Delay mission state machine.</description>
<param index="1">Delay in seconds (decimal)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_CONDITION_CHANGE_ALT" value="113">
<description>Ascend/descend at rate. Delay mission state machine until desired altitude reached.</description>
<param index="1">Descent / Ascend rate (m/s)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Finish Altitude</param>
</entry>
<entry name="MAV_CMD_CONDITION_DISTANCE" value="114">
<description>Delay mission state machine until within desired distance of next NAV point.</description>
<param index="1">Distance (meters)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_CONDITION_LAST" value="159">
<description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_SET_MODE" value="176">
<description>Set system mode.</description>
<param index="1">Mode, as defined by ENUM MAV_MODE</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_JUMP" value="177">
<description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description>
<param index="1">Sequence number</param>
<param index="2">Repeat count</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_CHANGE_SPEED" value="178">
<description>Change speed and/or throttle set points.</description>
<param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param>
<param index="2">Speed (m/s, -1 indicates no change)</param>
<param index="3">Throttle ( Percent, -1 indicates no change)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_SET_HOME" value="179">
<description>Changes the home location either to the current location or a specified location.</description>
<param index="1">Use current (1=use current location, 0=use specified location)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_DO_SET_PARAMETER" value="180">
<description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description>
<param index="1">Parameter number</param>
<param index="2">Parameter value</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_SET_RELAY" value="181">
<description>Set a relay to a condition.</description>
<param index="1">Relay number</param>
<param index="2">Setting (1=on, 0=off, others possible depending on system hardware)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_REPEAT_RELAY" value="182">
<description>Cycle a relay on and off for a desired number of cyles with a desired period.</description>
<param index="1">Relay number</param>
<param index="2">Cycle count</param>
<param index="3">Cycle time (seconds, decimal)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_SET_SERVO" value="183">
<description>Set a servo to a desired PWM value.</description>
<param index="1">Servo number</param>
<param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry name="MAV_CMD_DO_REPEAT_SERVO" value="184">
<description>Cycle a between its nominal setting and a desired PWM for a desired number of cyles with a desired period.</description>
<param index="1">Servo number</param>
<param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
<param index="3">Cycle count</param>
<param index="4">Cycle time (seconds)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
<enum name="MAV_DATA_STREAM">
<description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
recommendation to the autopilot software. Individual autopilots may or may not obey
the recommended messages.
</description>
<entry name="MAV_DATA_STREAM_ALL" value="0"><description>Enable all data streams</description></entry>
<entry name="MAV_DATA_STREAM_RAW_SENSORS" value="1"><description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description></entry>
<entry name="MAV_DATA_STREAM_EXTENDED_STATUS" value="2"><description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description></entry>
<entry name="MAV_DATA_STREAM_RC_CHANNELS" value="3"><description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description></entry>
<entry name="MAV_DATA_STREAM_RAW_CONTROLLER" value="4"><description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description></entry>
<entry name="MAV_DATA_STREAM_POSITION" value="6"><description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA1" value="250"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA2" value="251"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA3" value="252"><description>Dependent on the autopilot</description></entry>
</enum>
</enums>
<messages>
<message name="HEARTBEAT" id="0">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
@ -87,13 +323,27 @@
<field name="param_id" type="array[15]">Onboard parameter id</field>
<field name="param_value" type="float">Onboard parameter value</field>
</message>
<message name="RAW_IMU" id="28">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="xacc" type="int16_t">X acceleration (mg raw)</field>
<field name="yacc" type="int16_t">Y acceleration (mg raw)</field>
<field name="zacc" type="int16_t">Z acceleration (mg raw)</field>
<message name="GPS_RAW_INT" id="25">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="lat" type="int32_t">Latitude in 1E7 degrees</field>
<field name="lon" type="int32_t">Longitude in 1E7 degrees</field>
<field name="alt" type="int32_t">Altitude in 1E3 meters (millimeters)</field>
<field name="eph" type="float">GPS HDOP</field>
<field name="epv" type="float">GPS VDOP</field>
<field name="v" type="float">GPS ground speed (m/s)</field>
<field name="hdg" type="float">Compass heading in degrees, 0..360 degrees</field>
</message>
<message name="SCALED_IMU" id="26">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="xacc" type="int16_t">X acceleration (mg)</field>
<field name="yacc" type="int16_t">Y acceleration (mg)</field>
<field name="zacc" type="int16_t">Z acceleration (mg)</field>
<field name="xgyro" type="int16_t">Angular speed around X axis (millirad /sec)</field>
<field name="ygyro" type="int16_t">Angular speed around Y axis (millirad /sec)</field>
<field name="zgyro" type="int16_t">Angular speed around Z axis (millirad /sec)</field>
@ -101,52 +351,7 @@
<field name="ymag" type="int16_t">Y Magnetic field (milli tesla)</field>
<field name="zmag" type="int16_t">Z Magnetic field (milli tesla)</field>
</message>
<message name="RAW_PRESSURE" id="29">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, unscaled ADC values.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="press_abs" type="uint16_t">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="int16_t">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="int16_t">Differential pressure 2 (hectopascal)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement (0.01 degrees celsius per tick is default unit)</field>
</message>
<message name="ATTITUDE" id="30">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
<field name="usec" type="uint64_t">Timestamp (microseconds)</field>
<field name="roll" type="float">Roll angle (rad)</field>
<field name="pitch" type="float">Pitch angle (rad)</field>
<field name="yaw" type="float">Yaw angle (rad)</field>
<field name="rollspeed" type="float">Roll angular speed (rad/s)</field>
<field name="pitchspeed" type="float">Pitch angular speed (rad/s)</field>
<field name="yawspeed" type="float">Yaw angular speed (rad/s)</field>
</message>
<message name="LOCAL_POSITION" id="31">
<description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="x" type="float">X Position</field>
<field name="y" type="float">Y Position</field>
<field name="z" type="float">Z Position</field>
<field name="vx" type="float">X Speed</field>
<field name="vy" type="float">Y Speed</field>
<field name="vz" type="float">Z Speed</field>
</message>
<message name="GPS_RAW" id="32">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="lat" type="float">Latitude in degrees</field>
<field name="lon" type="float">Longitude in degrees</field>
<field name="alt" type="float">Altitude in meters</field>
<field name="eph" type="float">GPS HDOP</field>
<field name="epv" type="float">GPS VDOP</field>
<field name="v" type="float">GPS ground speed</field>
<field name="hdg" type="float">Compass heading in degrees, 0..360 degrees</field>
</message>
<message name="GPS_STATUS" id="27">
<description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description>
<field name="satellites_visible" type="uint8_t">Number of satellites visible</field>
@ -157,6 +362,51 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="satellite_snr" type="array[20]">Signal to noise ratio of satellite</field>
</message>
<message name="RAW_IMU" id="28">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="xacc" type="int16_t">X acceleration (raw)</field>
<field name="yacc" type="int16_t">Y acceleration (raw)</field>
<field name="zacc" type="int16_t">Z acceleration (raw)</field>
<field name="xgyro" type="int16_t">Angular speed around X axis (raw)</field>
<field name="ygyro" type="int16_t">Angular speed around Y axis (raw)</field>
<field name="zgyro" type="int16_t">Angular speed around Z axis (raw)</field>
<field name="xmag" type="int16_t">X Magnetic field (raw)</field>
<field name="ymag" type="int16_t">Y Magnetic field (raw)</field>
<field name="zmag" type="int16_t">Z Magnetic field (raw)</field>
</message>
<message name="RAW_PRESSURE" id="29">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, unscaled ADC values.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="press_abs" type="float">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="float">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="float">Differential pressure 2 (hectopascal)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement (0.01 degrees celsius per tick is default unit)</field>
</message>
<message name="ATTITUDE" id="30">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="roll" type="float">Roll angle (rad)</field>
<field name="pitch" type="float">Pitch angle (rad)</field>
<field name="yaw" type="float">Yaw angle (rad)</field>
<field name="rollspeed" type="float">Roll angular speed (rad/s)</field>
<field name="pitchspeed" type="float">Pitch angular speed (rad/s)</field>
<field name="yawspeed" type="float">Yaw angular speed (rad/s)</field>
</message>
<message name="LOCAL_POSITION" id="31">
<description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="x" type="float">X Position</field>
<field name="y" type="float">Y Position</field>
<field name="z" type="float">Z Position</field>
<field name="vx" type="float">X Speed</field>
<field name="vy" type="float">Y Speed</field>
<field name="vz" type="float">Z Speed</field>
</message>
<message name="GLOBAL_POSITION" id="33">
<description>The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
@ -168,6 +418,20 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="vz" type="float">Z Speed (in Altitude direction, positive: going up)</field>
</message>
<message name="GPS_RAW" id="32">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="lat" type="float">Latitude in degrees</field>
<field name="lon" type="float">Longitude in degrees</field>
<field name="alt" type="float">Altitude in meters</field>
<field name="eph" type="float">GPS HDOP</field>
<field name="epv" type="float">GPS VDOP</field>
<field name="v" type="float">GPS ground speed</field>
<field name="hdg" type="float">Compass heading in degrees, 0..360 degrees</field>
</message>
<message name="SYS_STATUS" id="34">
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
<field name="mode" type="uint8_t">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field>
@ -219,22 +483,21 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<message name="WAYPOINT" id="39">
<description>Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore y encodes in global mode the latitude, whereas x encodes the longitude and z the GPS altitude (WGS84).</description>
the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore y encodes in global mode the latitude, whereas x encodes the longitude and z the GPS altitude (WGS84).</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
<field name="frame" type="uint8_t">The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h</field>
<field name="action" type="uint8_t">The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h</field>
<field name="orbit" type="float">Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint</field>
<field name="orbit_direction" type="uint8_t">Direction of the orbit circling: 0: clockwise, 1: counter-clockwise</field>
<field name="param1" type="float">For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters</field>
<field name="param2" type="float">For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds</field>
<field name="command" type="uint8_t">The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs</field>
<field name="current" type="uint8_t">false:0, true:1</field>
<field name="x" type="float">local: x position, global: longitude</field>
<field name="y" type="float">y position: global: latitude</field>
<field name="z" type="float">z position: global: altitude</field>
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
<field name="autocontinue" type="uint8_t">autocontinue to next wp</field>
<field name="param1" type="float">PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters</field>
<field name="param2" type="float">PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
<field name="param3" type="float">PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
<field name="param4" type="float">PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
<field name="x" type="float">PARAM5 / local: x position, global: longitude</field>
<field name="y" type="float">PARAM6 / y position: global: latitude</field>
<field name="z" type="float">PARAM7 / z position: global: altitude</field>
</message>
<message name="WAYPOINT_REQUEST" id="40">
@ -287,36 +550,41 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="type" type="uint8_t">0: OK, 1: Error</field>
</message>
<message name="WAYPOINT_SET_GLOBAL_REFERENCE" id="48">
<message name="GPS_SET_GLOBAL_ORIGIN" id="48">
<description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="global_x" type="float">global x position</field>
<field name="global_y" type="float">global y position</field>
<field name="global_z" type="float">global z position</field>
<field name="global_yaw" type="float">global yaw orientation in radians, 0 = NORTH</field>
<field name="global_x" type="uint32_t">global x position * 1E7</field>
<field name="global_y" type="uint32_t">global y position * 1E7</field>
<field name="global_z" type="uint32_t">global z position * 1000</field>
<field name="local_x" type="float">local x position that matches the global x position</field>
<field name="local_y" type="float">local y position that matches the global y position</field>
<field name="local_z" type="float">local z position that matches the global z position</field>
<field name="local_yaw" type="float">local yaw that matches the global yaw orientation</field>
</message>
<message name="GPS_LOCAL_ORIGIN_SET" id="49">
<description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description>
<field name="latitude" type="int32_t">Latitude (WGS84), expressed as * 1E7</field>
<field name="longitude" type="int32_t">Longitude (WGS84), expressed as * 1E7</field>
<field name="altitude" type="int32_t">Altitude(WGS84), expressed as * 1000</field>
</message>
<message name="LOCAL_POSITION_SETPOINT_SET" id="50">
<description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="x" type="float">x position 1</field>
<field name="y" type="float">y position 1</field>
<field name="z" type="float">z position 1</field>
<field name="yaw" type="float">x position 2</field>
<field name="x" type="float">x position</field>
<field name="y" type="float">y position</field>
<field name="z" type="float">z position</field>
<field name="yaw" type="float">Desired yaw angle</field>
</message>
<message name="LOCAL_POSITION_SETPOINT" id="51">
<description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description>
<field name="x" type="float">x position 1</field>
<field name="y" type="float">y position 1</field>
<field name="z" type="float">z position 1</field>
<field name="yaw" type="float">x position 2</field>
<field name="x" type="float">x position</field>
<field name="y" type="float">y position</field>
<field name="z" type="float">z position</field>
<field name="yaw" type="float">Desired yaw angle</field>
</message>
<message name="CONTROL_STATUS" id="52">
@ -382,6 +650,7 @@ of the controller before actual flight and to assist with tuning controller para
<field name="wp_dist" type="uint16_t">Distance to active waypoint in meters</field>
<field name="alt_error" type="float">Current altitude error in meters</field>
<field name="aspd_error" type="float">Current airspeed error in meters/second</field>
<field name="xtrack_error" type="float">Current crosstrack error on x-y plane in meters</field>
</message>
<message name="POSITION_TARGET" id="63">
@ -430,18 +699,11 @@ of the controller before actual flight and to assist with tuning controller para
<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
</message>
<message name="GPS_LOCAL_ORIGIN_SET" id="71">
<description>Once the MAV sets a new GPS-Local correspondence, this message announces </description>
<field name="latitude" type="int32_t">Latitude (WGS84), expressed as * 1E7</field>
<field name="longitude" type="int32_t">Longitude (WGS84), expressed as * 1E7</field>
<field name="altitude" type="int32_t">Altitude(WGS84), expressed as * 1000</field>
</message>
<message name="GLOBAL_POSITION_INT" id="73">
<description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description>
<field name="lat" type="int32_t">Latitude / X Position, expressed as * 1E7</field>
<field name="lon" type="int32_t">Longitude / Y Position, expressed as * 1E7</field>
<field name="alt" type="int32_t">Altitude / negative Z Position, expressed as * 1000</field>
<field name="alt" type="int32_t">Altitude in meters, expressed as * 1000 (millimeters)</field>
<field name="vx" type="int16_t">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field name="vy" type="int16_t">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<field name="vz" type="int16_t">Ground Z Speed (Altitude), expressed as m/s * 100</field>
@ -451,10 +713,10 @@ of the controller before actual flight and to assist with tuning controller para
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
<field name="airspeed" type="float">Current airspeed in m/s</field>
<field name="groundspeed" type="float">Current ground speed in m/s</field>
<field name="heading" type="int16_t">Current heading in degrees</field>
<field name="alt" type="uint16_t">Current altitude (MSL), in meters</field>
<field name="climb" type="float">Current climb rate in meters/second</field>
<field name="heading" type="int16_t">Current heading in degrees, in compass units (0..360, 0=north)</field>
<field name="throttle" type="uint16_t">Current throttle setting in integer percent, 0 to 100</field>
<field name="alt" type="float">Current altitude (MSL), in meters</field>
<field name="climb" type="float">Current climb rate in meters/second</field>
</message>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->

View File

@ -9,6 +9,13 @@
<entry name = "PID_PITCH">With comment: PID Pitch parameter</entry>
<entry name = "PID_ALT_HOLD" value="50" />
</enum>
<enum name="DATA_TYPES">
<description>Content Types for data transmission handshake</description>
<entry name = "DATA_TYPE_JPEG_IMAGE" value="1" />
<entry name = "DATA_TYPE_RAW_IMAGE" value="2" />
<entry name = "DATA_TYPE_KINECT" />
</enum>
</enums>
<messages>