Skip to content

Commit

Permalink
added SenseSoar Mavlink Messages
Browse files Browse the repository at this point in the history
  • Loading branch information
oberion committed Aug 2, 2011
1 parent 0641c63 commit 241d6c3
Show file tree
Hide file tree
Showing 26 changed files with 2,313 additions and 3 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -51,3 +51,4 @@ user_config.pri
thirdParty/qserialport-build-desktop/
thirdParty/qserialport/bin/
thirdParty/qserialport/lib/
thirdParty/libxbee/lib
10 changes: 10 additions & 0 deletions qgroundcontrol.pro
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,16 @@ contains(MAVLINK_CONF, ardupilotmega) {
INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/ardupilotmega
DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES
}
contains(MAVLINK_CONF, senseSoar) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common

# SENSESOAR SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/SenseSoar
INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/SenseSoar
DEFINES += QGC_USE_SENSESOAR_MESSAGES
}


# Include general settings for QGroundControl
Expand Down
73 changes: 73 additions & 0 deletions thirdParty/mavlink/include/SenseSoar/SenseSoar.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef SENSESOAR_H
#define SENSESOAR_H

#ifdef __cplusplus
extern "C" {
#endif


#include "../protocol.h"

#define MAVLINK_ENABLED_SENSESOAR


#include "../common/common.h"
// MAVLINK VERSION

#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif

#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif

// ENUM DEFINITIONS

/** @brief Different flight modes */
enum SENSESOAR_MODE
{
SENSESOAR_MODE_GLIDING=0, /* */
SENSESOAR_MODE_AUTONOMOUS=1, /* */
SENSESOAR_MODE_MANUAL=2, /* */
SENSESOAR_MODE_ENUM_END
};


// MESSAGE DEFINITIONS

#include "./mavlink_msg_sensesoar_mode_chng.h"
#include "./mavlink_msg_sensesoar_mode_ack.h"
#include "./mavlink_msg_sensesoar_mode_rqst.h"
#include "./mavlink_msg_sensesoar_mode_rqst_send.h"
#include "./mavlink_msg_obs_position.h"
#include "./mavlink_msg_obs_velocity.h"
#include "./mavlink_msg_obs_attitude.h"
#include "./mavlink_msg_obs_wind.h"
#include "./mavlink_msg_obs_air_velocity.h"
#include "./mavlink_msg_obs_bias.h"
#include "./mavlink_msg_obs_qff.h"
#include "./mavlink_msg_obs_air_temp.h"
#include "./mavlink_msg_filt_rot_vel.h"
#include "./mavlink_msg_llc_out.h"
#include "./mavlink_msg_pm_elec.h"
#include "./mavlink_msg_sys_stat.h"
#include "./mavlink_msg_cmd_airspeed_chng.h"
#include "./mavlink_msg_cmd_airspeed_ack.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, 2, 2, 1, 1, 24, 0, 12, 0, 16, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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
#endif
11 changes: 11 additions & 0 deletions thirdParty/mavlink/include/SenseSoar/mavlink.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

#include "SenseSoar.h"

#endif
123 changes: 123 additions & 0 deletions thirdParty/mavlink/include/SenseSoar/mavlink_msg_cmd_airspeed_ack.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,123 @@
// MESSAGE CMD_AIRSPEED_ACK PACKING

#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK 194

typedef struct __mavlink_cmd_airspeed_ack_t
{
float spCmd; ///< commanded airspeed
uint8_t ack; ///< 0:ack, 1:nack

} mavlink_cmd_airspeed_ack_t;



/**
* @brief Pack a cmd_airspeed_ack 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 spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float spCmd, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;

i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack

return mavlink_finalize_message(msg, system_id, component_id, i);
}

/**
* @brief Pack a cmd_airspeed_ack 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 spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float spCmd, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;

i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack

return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}

/**
* @brief Encode a cmd_airspeed_ack 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 cmd_airspeed_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack);
}

/**
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack)
{
mavlink_message_t msg;
mavlink_msg_cmd_airspeed_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, spCmd, ack);
mavlink_send_uart(chan, &msg);
}

#endif
// MESSAGE CMD_AIRSPEED_ACK UNPACKING

/**
* @brief Get field spCmd from cmd_airspeed_ack message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(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 Get field ack from cmd_airspeed_ack message
*
* @return 0:ack, 1:nack
*/
static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(float))[0];
}

/**
* @brief Decode a cmd_airspeed_ack message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg);
cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg);
}
123 changes: 123 additions & 0 deletions thirdParty/mavlink/include/SenseSoar/mavlink_msg_cmd_airspeed_chng.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,123 @@
// MESSAGE CMD_AIRSPEED_CHNG PACKING

#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192

typedef struct __mavlink_cmd_airspeed_chng_t
{
uint8_t target; ///< Target ID
float spCmd; ///< commanded airspeed

} mavlink_cmd_airspeed_chng_t;



/**
* @brief Pack a cmd_airspeed_chng 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 Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float spCmd)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;

i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed

return mavlink_finalize_message(msg, system_id, component_id, i);
}

/**
* @brief Pack a cmd_airspeed_chng 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 Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float spCmd)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;

i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed

return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}

/**
* @brief Encode a cmd_airspeed_chng 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 cmd_airspeed_chng C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd);
}

/**
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param spCmd commanded airspeed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd)
{
mavlink_message_t msg;
mavlink_msg_cmd_airspeed_chng_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, spCmd);
mavlink_send_uart(chan, &msg);
}

#endif
// MESSAGE CMD_AIRSPEED_CHNG UNPACKING

/**
* @brief Get field target from cmd_airspeed_chng message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}

/**
* @brief Get field spCmd from cmd_airspeed_chng message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (float)r.f;
}

/**
* @brief Decode a cmd_airspeed_chng message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_chng C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg);
cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg);
}
Loading

0 comments on commit 241d6c3

Please sign in to comment.