Commit 6e064749 authored by oberion's avatar oberion

Merge remote-tracking branch 'remotes/pixhawk/dev-win' into dev-win

parents 9136d539 71eb9a58
......@@ -402,9 +402,9 @@ DEFINES += QGC_OSG_ENABLED
QMAKE_POST_LINK += $$quote(copy /Y "$$(QTDIR)\\bin\\QtWebKit4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$(QTDIR)\\bin\\QtXml4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$(QTDIR)\\bin\\QtXmlPatterns4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(del /F "$$TARGETDIR_WIN\\release\\qgroundcontrol.exp"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(del /F "$$TARGETDIR_WIN\\release\\qgroundcontrol.lib"$$escape_expand(\\n))
}
}
# Windows (32bit)
......
......@@ -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_ENU = 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,
PID_PITCH=3, /* With comment: PID Pitch parameter*/
PID_ALT_HOLD=50,
SLUGS_PID_INDX_IDS_ENUM_END
};
/** @brief Content Types for data transmission handshake */
/** @brief Content Types for data transmission handshake */
enum DATA_TYPES
{
DATA_TYPE_JPEG_IMAGE=1,
......@@ -58,6 +49,7 @@ enum DATA_TYPES
#include "./mavlink_msg_image_available.h"
#include "./mavlink_msg_vision_position_estimate.h"
#include "./mavlink_msg_vicon_position_estimate.h"
#include "./mavlink_msg_vision_speed_estimate.h"
#include "./mavlink_msg_position_control_setpoint_set.h"
#include "./mavlink_msg_position_control_offset_set.h"
#include "./mavlink_msg_position_control_setpoint.h"
......@@ -74,6 +66,13 @@ enum DATA_TYPES
#include "./mavlink_msg_data_transmission_handshake.h"
#include "./mavlink_msg_encapsulated_data.h"
#include "./mavlink_msg_brief_feature.h"
// 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, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 0, 0, 32, 32, 20, 0, 0, 0, 0, 0, 0, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 12, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 18, 0, 0, 0, 0, 0, 106, 42, 54, 0, 0, 0, 0, 0, 0, 0, 8, 255, 53, 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
......
/** @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 SLUGS_H
#define SLUGS_H
......@@ -43,6 +43,13 @@ extern "C" {
#include "./mavlink_msg_mid_lvl_cmds.h"
#include "./mavlink_msg_ctrl_srfc_pt.h"
#include "./mavlink_msg_slugs_action.h"
// 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, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 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
......
// MESSAGE UALBERTA_SYS_STATUS PACKING
#define MAVLINK_MSG_ID_UALBERTA_SYS_STATUS 222
typedef struct __mavlink_ualberta_sys_status_t
{
uint8_t mode; ///< System mode, see UALBERTA_AUTOPILOT_MODE ENUM
uint8_t nav_mode; ///< Navigation mode, see UALBERTA_NAV_MODE ENUM
uint8_t pilot; ///< Pilot mode, see UALBERTA_PILOT_MODE
} mavlink_ualberta_sys_status_t;
/**
* @brief Pack a ualberta_sys_status 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 mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM
* @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM
* @param pilot Pilot mode, see UALBERTA_PILOT_MODE
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ualberta_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t pilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS;
i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see UALBERTA_AUTOPILOT_MODE ENUM
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see UALBERTA_NAV_MODE ENUM
i += put_uint8_t_by_index(pilot, i, msg->payload); // Pilot mode, see UALBERTA_PILOT_MODE
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a ualberta_sys_status 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 mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM
* @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM
* @param pilot Pilot mode, see UALBERTA_PILOT_MODE
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ualberta_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t pilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS;
i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see UALBERTA_AUTOPILOT_MODE ENUM
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see UALBERTA_NAV_MODE ENUM
i += put_uint8_t_by_index(pilot, i, msg->payload); // Pilot mode, see UALBERTA_PILOT_MODE
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a ualberta_sys_status 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 ualberta_sys_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ualberta_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ualberta_sys_status_t* ualberta_sys_status)
{
return mavlink_msg_ualberta_sys_status_pack(system_id, component_id, msg, ualberta_sys_status->mode, ualberta_sys_status->nav_mode, ualberta_sys_status->pilot);
}
/**
* @brief Send a ualberta_sys_status message
* @param chan MAVLink channel to send the message
*
* @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM
* @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM
* @param pilot Pilot mode, see UALBERTA_PILOT_MODE
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ualberta_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t pilot)
{
mavlink_message_t msg;
mavlink_msg_ualberta_sys_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, nav_mode, pilot);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE UALBERTA_SYS_STATUS UNPACKING
/**
* @brief Get field mode from ualberta_sys_status message
*
* @return System mode, see UALBERTA_AUTOPILOT_MODE ENUM
*/
static inline uint8_t mavlink_msg_ualberta_sys_status_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field nav_mode from ualberta_sys_status message
*
* @return Navigation mode, see UALBERTA_NAV_MODE ENUM
*/
static inline uint8_t mavlink_msg_ualberta_sys_status_get_nav_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field pilot from ualberta_sys_status message
*
* @return Pilot mode, see UALBERTA_PILOT_MODE
*/
static inline uint8_t mavlink_msg_ualberta_sys_status_get_pilot(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a ualberta_sys_status message into a struct
*
* @param msg The message to decode
* @param ualberta_sys_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_ualberta_sys_status_decode(const mavlink_message_t* msg, mavlink_ualberta_sys_status_t* ualberta_sys_status)
{
ualberta_sys_status->mode = mavlink_msg_ualberta_sys_status_get_mode(msg);
ualberta_sys_status->nav_mode = mavlink_msg_ualberta_sys_status_get_nav_mode(msg);
ualberta_sys_status->pilot = mavlink_msg_ualberta_sys_status_get_pilot(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 UALBERTA_H
#define UALBERTA_H
......@@ -30,12 +30,49 @@ extern "C" {
// ENUM DEFINITIONS
/** @brief Available autopilot modes for ualberta uav */
enum UALBERTA_AUTOPILOT_MODE
{
MODE_MANUAL_DIRECT=0, /* */
MODE_MANUAL_SCALED=1, /* */
MODE_AUTO_PID_ATT=2, /* */
MODE_AUTO_PID_VEL=3, /* */
MODE_AUTO_PID_POS=4, /* */
UALBERTA_AUTOPILOT_MODE_ENUM_END
};
/** @brief Navigation filter mode */
enum UALBERTA_NAV_MODE
{
NAV_AHRS_INIT=0,
NAV_AHRS=1, /* */
NAV_INS_GPS_INIT=2, /* */
NAV_INS_GPS=3, /* */
UALBERTA_NAV_MODE_ENUM_END
};
/** @brief Mode currently commanded by pilot */
enum UALBERTA_PILOT_MODE
{
PILOT_MANUAL=0, /* */
PILOT_AUTO=1, /* */
PILOT_ROTO=2, /* */
UALBERTA_PILOT_MODE_ENUM_END
};
// MESSAGE DEFINITIONS
#include "./mavlink_msg_nav_filter_bias.h"
#include "./mavlink_msg_request_rc_channels.h"
#include "./mavlink_msg_radio_calibration.h"
#include "./mavlink_msg_ualberta_sys_status.h"
// 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, 32, 42, 3, 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
......
......@@ -79,17 +79,21 @@
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry name="MAV_CMD_NAV_ORIENTATION_TARGET" value="80">
<description>Set the location the system should be heading towards (camera heads or
rotary wing aircraft).</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<entry name="MAV_CMD_NAV_ROI" value="80">
<description>Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
sensors such as cameras.</description>
<param index="1">Region of intereset mode. (see MAV_ROI enum)</param>
<param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param>
<param index="3">ROI index (allows a vehicle to manage multiple ROI's)</param>
<param index="4">Empty</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
<param index="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<param index="6">y</param>
<param index="7">z</param>
</entry>
<entry name="MAV_CMD_NAV_PATHPLANNING" value="81">
<description>Control autonomous path planning on the MAV.</description>
<param index="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param>
......@@ -306,6 +310,18 @@
<entry name="MAV_DATA_STREAM_EXTRA2" value="11"><description>Dependent on the autopilot</description></entry>
<entry name="MAV_DATA_STREAM_EXTRA3" value="12"><description>Dependent on the autopilot</description></entry>
</enum>
<enum name="MAV_ROI">
<description> The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI).
</description>
<entry name="MAV_ROI_WPNEXT" value="0"><description>Point toward next waypoint.</description></entry>
<entry name="MAV_ROI_WPINDEX" value="1"><description>Point toward given waypoint.</description></entry>
<entry name="MAV_ROI_LOCATION" value="2"><description>Point toward fixed location.</description></entry>
<entry name="MAV_ROI_TARGET" value="3"><description>Point toward of given id.</description></entry>
</enum>
</enums>
<messages>
......
<?xml version='1.0'?>
<mavlink>
<version>2</version>
<enums/>
<messages>
<message id="0" name="HEARTBEAT">
<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>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field>
</message>
</messages>
</mavlink>
......@@ -3,18 +3,14 @@
<include>common.xml</include>
<enums>
<enum name="SLUGS_PID_INDX_IDS" >
<description>Slugs parameter interface subsets</description>
<entry name = "PID_YAW_DAMPER" value="2" />
<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" />
<entry name = "DATA_TYPE_JPEG_IMAGE" value="1">
</entry>
<entry name = "DATA_TYPE_RAW_IMAGE" value="2">
</entry>
<entry name = "DATA_TYPE_KINECT" value="3">
</entry>
</enum>
</enums>
......@@ -50,6 +46,9 @@
<field name="lat" type="float">GPS X coordinate</field>
<field name="lon" type="float">GPS Y coordinate</field>
<field name="alt" type="float">Global frame altitude</field>
<field name="ground_x" type="float">Ground truth X</field>
<field name="ground_y" type="float">Ground truth Y</field>
<field name="ground_z" type="float">Ground truth Z</field>
</message>
<message name="IMAGE_TRIGGER_CONTROL" id="102">
......@@ -77,6 +76,9 @@
<field name="lat" type="float">GPS X coordinate</field>
<field name="lon" type="float">GPS Y coordinate</field>
<field name="alt" type="float">Global frame altitude</field>
<field name="ground_x" type="float">Ground truth X</field>
<field name="ground_y" type="float">Ground truth Y</field>
<field name="ground_z" type="float">Ground truth Z</field>
</message>
<message name="VISION_POSITION_ESTIMATE" id="111">
......@@ -99,6 +101,13 @@
<field name="yaw" type="float">Yaw angle in rad</field>
</message>
<message name="VISION_SPEED_ESTIMATE" id="113">
<field name="usec" type="uint64_t">Timestamp (milliseconds)</field>
<field name="x" type="float">Global X speed</field>
<field name="y" type="float">Global Y speed</field>
<field name="z" type="float">Global Z speed</field>
</message>
<message name="POSITION_CONTROL_SETPOINT_SET" id="120">
<description>Message sent to the MAV to set a new position as reference for the controller</description>
<field name="target_system" type="uint8_t">System ID</field>
......
<?xml version="1.0"?>
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<messages>
<message name="NAV_FILTER_BIAS" id="220">
<description>Accelerometer and Gyro biases from the navigation filter</description>
<field name="usec" type="uint64_t">Timestamp (microseconds)</field>
<field name="accel_0" type="float">b_f[0]</field>
<field name="accel_1" type="float">b_f[1]</field>
<field name="accel_2" type="float">b_f[2]</field>
<field name="gyro_0" type="float">b_f[0]</field>
<field name="gyro_1" type="float">b_f[1]</field>
<field name="gyro_2" type="float">b_f[2]</field>
</message>
<message name="REQUEST_RC_CHANNELS" id="221">
<description>Request raw and normalized rc data from the UAV</description>
<field name="enabled" type="uint8_t">True: start sending data; False: stop sending data</field>
</message>
<message name="RADIO_CALIBRATION" id="222">
<description>Complete set of calibration parameters for the radio</description>
<field name="aileron" type="float[3]">Aileron setpoints: high, center, low</field>
<field name="elevator" type="float[3]">Elevator setpoints: high, center, low</field>
<field name="rudder" type="float[3]">Rudder setpoints: high, center, low</field>
<field name="gyro" type="float[2]">Tail gyro mode/gain setpoints: heading hold, rate mode</field>
<field name="pitch" type="float[5]">Pitch curve setpoints (every 25%)</field>
<field name="throttle" type="float[5]">Throttle curve setpoints (every 25%)</field>
</message>
</messages>
<include>common.xml</include>
<enums>
<enum name="UALBERTA_AUTOPILOT_MODE">
<description>Available autopilot modes for ualberta uav</description>
<entry name="MODE_MANUAL_DIRECT">Raw input pulse widts sent to output</entry>
<entry name="MODE_MANUAL_SCALED">Inputs are normalized using calibration, the converted back to raw pulse widths for output</entry>
<entry name="MODE_AUTO_PID_ATT"> dfsdfs</entry>
<entry name="MODE_AUTO_PID_VEL"> dfsfds</entry>
<entry name="MODE_AUTO_PID_POS"> dfsdfsdfs</entry>
</enum>
<enum name="UALBERTA_NAV_MODE">
<description>Navigation filter mode</description>
<entry name="NAV_AHRS_INIT" />
<entry name="NAV_AHRS">AHRS mode</entry>
<entry name="NAV_INS_GPS_INIT">INS/GPS initialization mode</entry>
<entry name="NAV_INS_GPS">INS/GPS mode</entry>
</enum>
<enum name="UALBERTA_PILOT_MODE">
<description>Mode currently commanded by pilot</description>
<entry name="PILOT_MANUAL"> sdf</entry>
<entry name="PILOT_AUTO"> dfs</entry>
<entry name="PILOT_ROTO"> Rotomotion mode </entry>
</enum>
</enums>
<messages>
<message id="220" name="NAV_FILTER_BIAS">
<description>Accelerometer and Gyro biases from the navigation filter</description>
<field type="uint64_t" name="usec">Timestamp (microseconds)</field>
<field type="float" name="accel_0">b_f[0]</field>
<field type="float" name="accel_1">b_f[1]</field>
<field type="float" name="accel_2">b_f[2]</field>
<field type="float" name="gyro_0">b_f[0]</field>
<field type="float" name="gyro_1">b_f[1]</field>
<field type="float" name="gyro_2">b_f[2]</field>
</message>
<message id="221" name="RADIO_CALIBRATION">
<description>Complete set of calibration parameters for the radio</description>
<field type="uint16_t[3]" name="aileron">Aileron setpoints: left, center, right</field>
<field type="uint16_t[3]" name="elevator">Elevator setpoints: nose down, center, nose up</field>
<field type="uint16_t[3]" name="rudder">Rudder setpoints: nose left, center, nose right</field>
<field type="uint16_t[2]" name="gyro">Tail gyro mode/gain setpoints: heading hold, rate mode</field>
<field type="uint16_t[5]" name="pitch">Pitch curve setpoints (every 25%)</field>
<field type="uint16_t[5]" name="throttle">Throttle curve setpoints (every 25%)</field>
</message>
<message id="222" name="UALBERTA_SYS_STATUS">
<description>System status specific to ualberta uav</description>
<field type="uint8_t" name="mode">System mode, see UALBERTA_AUTOPILOT_MODE ENUM</field>
<field type="uint8_t" name="nav_mode">Navigation mode, see UALBERTA_NAV_MODE ENUM</field>
<field type="uint8_t" name="pilot">Pilot mode, see UALBERTA_PILOT_MODE</field>
</message>
</messages>
</mavlink>
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment