Commit 2b45108d authored by LM's avatar LM

Added most recent MAVLink

parent ce45adce
......@@ -676,7 +676,7 @@ void QGCParamWidget::retransmissionGuardTick()
*/
void QGCParamWidget::requestParameterUpdate(int component, const QString& parameter)
{
// FIXME - IMPLEMENT THIS!
}
......
......@@ -12,6 +12,8 @@ Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMa
showOrbit(false),
color(Qt::red)
{
Q_UNUSED(name);
SetHeading(0);
SetNumber(listindex);
this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, March 31 2011, 22:06 UTC
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
......@@ -33,6 +33,13 @@ extern "C" {
// MESSAGE DEFINITIONS
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
#ifdef __cplusplus
}
#endif
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, March 31 2011, 22:06 UTC
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
This diff is collapsed.
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, March 31 2011, 22:06 UTC
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -13,6 +13,7 @@ enum MAV_CLASS
MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
MAV_CLASS_NONE = 8, ///< No valid autopilot
MAV_CLASS_NB ///< Number of autopilot classes
};
......@@ -101,7 +102,8 @@ enum MAV_NAV
MAV_NAV_RETURNING,
MAV_NAV_LANDING,
MAV_NAV_LOST,
MAV_NAV_LOITER
MAV_NAV_LOITER,
MAV_NAV_FREE_DRIFT
};
enum MAV_TYPE
......@@ -112,7 +114,12 @@ enum MAV_TYPE
MAV_COAXIAL = 3,
MAV_HELICOPTER = 4,
MAV_GROUND = 5,
OCU = 6
OCU = 6,
MAV_AIRSHIP = 7,
MAV_FREE_BALLOON = 8,
MAV_ROCKET = 9,
UGV_GROUND_ROVER = 10,
UGV_SURFACE_SHIP = 11
};
enum MAV_AUTOPILOT_TYPE
......@@ -120,7 +127,8 @@ enum MAV_AUTOPILOT_TYPE
MAV_AUTOPILOT_GENERIC = 0,
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
MAV_AUTOPILOT_NONE = 4
};
enum MAV_COMPONENT
......@@ -133,6 +141,8 @@ enum MAV_COMPONENT
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_IMU_2 = 201,
MAV_COMP_ID_IMU_3 = 202,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
......@@ -143,7 +153,19 @@ enum MAV_FRAME
MAV_FRAME_GLOBAL = 0,
MAV_FRAME_LOCAL = 1,
MAV_FRAME_MISSION = 2,
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
MAV_FRAME_LOCAL_Z_UP = 4
};
enum MAVLINK_DATA_STREAM_TYPE
{
MAVLINK_DATA_STREAM_IMG_JPEG,
MAVLINK_DATA_STREAM_IMG_BMP,
MAVLINK_DATA_STREAM_IMG_RAW8U,
MAVLINK_DATA_STREAM_IMG_RAW32U,
MAVLINK_DATA_STREAM_IMG_PGM,
MAVLINK_DATA_STREAM_IMG_PNG
};
#define MAVLINK_STX 0x55 ///< Packet start sign
......@@ -165,6 +187,7 @@ typedef struct __mavlink_system {
uint8_t type; ///< Unused, can be used by user to store the system's type
uint8_t state; ///< Unused, can be used by user to store the system's state
uint8_t mode; ///< Unused, can be used by user to store the system's mode
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
} mavlink_system_t;
typedef struct __mavlink_message {
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#include "minimal.h"
#endif
// MESSAGE HEARTBEAT PACKING
#define MAVLINK_MSG_ID_HEARTBEAT 0
typedef struct __mavlink_heartbeat_t
{
uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
uint8_t mavlink_version; ///< MAVLink version
} mavlink_heartbeat_t;
/**
* @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
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(2, i, msg->payload); // MAVLink version
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t autopilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
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(2, i, msg->payload); // MAVLink version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot);
}
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
{
mavlink_message_t msg;
mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE HEARTBEAT UNPACKING
/**
* @brief Get field type from heartbeat message
*
* @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field autopilot from heartbeat message
*
* @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mavlink_version from heartbeat message
*
* @return MAVLink version
*/
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a heartbeat message into a struct
*
* @param msg The message to decode
* @param heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
}
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef MINIMAL_H
#define MINIMAL_H
#ifdef __cplusplus
extern "C" {
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_MINIMAL
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
// ENUM DEFINITIONS
// MESSAGE DEFINITIONS
#include "./mavlink_msg_heartbeat.h"
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { }
#ifdef __cplusplus
}
#endif
#endif
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, March 31 2011, 22:06 UTC
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -13,6 +13,9 @@ typedef struct __mavlink_image_triggered_t
float lat; ///< GPS X coordinate
float lon; ///< GPS Y coordinate
float alt; ///< Global frame altitude
float ground_x; ///< Ground truth X
float ground_y; ///< Ground truth Y
float ground_z; ///< Ground truth Z
} mavlink_image_triggered_t;
......@@ -33,9 +36,12 @@ typedef struct __mavlink_image_triggered_t
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @param ground_x Ground truth X
* @param ground_y Ground truth Y
* @param ground_z Ground truth Z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
......@@ -49,6 +55,9 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8
i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X
i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y
i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z
return mavlink_finalize_message(msg, system_id, component_id, i);
}
......@@ -68,9 +77,12 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @param ground_x Ground truth X
* @param ground_y Ground truth Y
* @param ground_z Ground truth Z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
......@@ -84,6 +96,9 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id,
i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X
i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y
i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
......@@ -98,7 +113,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id,
*/
static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered)
{
return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt);
return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z);
}
/**
......@@ -114,13 +129,16 @@ static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uin
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @param ground_x Ground truth X
* @param ground_y Ground truth Y
* @param ground_z Ground truth Z
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
{
mavlink_message_t msg;
mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt);
mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z);
mavlink_send_uart(chan, &msg);
}
......@@ -266,6 +284,51 @@ static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t*
return (float)r.f;
}
/**
* @brief Get field ground_x from image_triggered message
*
* @return Ground truth X
*/
static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field ground_y from image_triggered message
*
* @return Ground truth Y
*/
static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field ground_z from image_triggered message
*
* @return Ground truth Z
*/
static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a image_triggered message into a struct
*
......@@ -283,4 +346,7 @@ static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* m
image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg);
image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg);
image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg);
image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg);
image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg);
image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg);
}
// MESSAGE VISION_SPEED_ESTIMATE PACKING
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 113
typedef struct __mavlink_vision_speed_estimate_t
{
uint64_t usec; ///< Timestamp (milliseconds)
float x; ///< Global X speed
float y; ///< Global Y speed
float z; ///< Global Z speed
} mavlink_vision_speed_estimate_t;
/**
* @brief Pack a vision_speed_estimate 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 (milliseconds)
* @param x Global X speed
* @param y Global Y speed
* @param z Global Z speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); // Global X speed
i += put_float_by_index(y, i, msg->payload); // Global Y speed
i += put_float_by_index(z, i, msg->payload); // Global Z speed
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a vision_speed_estimate 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 (milliseconds)
* @param x Global X speed
* @param y Global Y speed
* @param z Global Z speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); // Global X speed
i += put_float_by_index(y, i, msg->payload); // Global Y speed
i += put_float_by_index(z, i, msg->payload); // Global Z speed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a vision_speed_estimate 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 vision_speed_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
{
return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
}
/**
* @brief Send a vision_speed_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X speed
* @param y Global Y speed
* @param z Global Z speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z)
{
mavlink_message_t msg;
mavlink_msg_vision_speed_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE VISION_SPEED_ESTIMATE UNPACKING
/**
* @brief Get field usec from vision_speed_estimate message
*
* @return Timestamp (milliseconds)
*/
static inline uint64_t mavlink_msg_vision_speed_estimate_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 x from vision_speed_estimate message
*
* @return Global X speed
*/
static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg)
{
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;
}
/**
* @brief Get field y from vision_speed_estimate message
*
* @return Global Y speed
*/
static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg)
{
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;
}
/**
* @brief Get field z from vision_speed_estimate message
*
* @return Global Z speed
*/
static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg)
{
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;
}
/**
* @brief Decode a vision_speed_estimate message into a struct
*
* @param msg The message to decode
* @param vision_speed_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate)
{
vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg);
vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg);
vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg);
}
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, March 31 2011, 22:06 UTC
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wednesday, July 27 2011, 14:17 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H
......@@ -30,16 +30,7 @@ extern "C" {
// ENUM DEFINITIONS
/** @brief Slugs parameter interface subsets */
enum SLUGS_PID_INDX_IDS
{
PID_YAW_DAMPER=2,