Commit d80f8c9b authored by oberion's avatar oberion

SenseSoar messages included

parent 241d6c36
......@@ -281,6 +281,7 @@ HEADERS += src/MG.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/uas/senseSoarMAV.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
src/ui/watchdog/WatchdogView.h \
......@@ -409,6 +410,7 @@ SOURCES += src/main.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/uas/senseSoarMAV.cpp \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
src/ui/watchdog/WatchdogView.cc \
......
......@@ -64,6 +64,14 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav;
}
break;
case MAV_AUTOPILOT_SENSESOAR:
{
senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
mav->setSystemType((int)heartbeat->type);
connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
break;
}
default: {
UAS* mav = new UAS(mavlink, sysid);
mav->setSystemType((int)heartbeat->type);
......
......@@ -12,6 +12,7 @@
#include "UAS.h"
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
#include "senseSoarMAV.h"
#include "ArduPilotMegaMAV.h"
class QGCMAVLinkUASFactory : public QObject
......
#include "senseSoarMAV.h"
#include <qmath.h>
senseSoarMAV::senseSoarMAV(MAVLinkProtocol* mavlink, int id)
: UAS(mavlink, id)
{
}
senseSoarMAV::~senseSoarMAV(void)
{
}
void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message)
{
#ifdef MAVLINK_ENABLED_SENSESOAR
if (message.sysid == uasId) // make sure the message is for the right UAV
{
if (!link) return;
switch (message.msgid)
{
case MAVLINK_MSG_ID_CMD_AIRSPEED_ACK: // TO DO: check for acknowledgement after sended commands
{
mavlink_cmd_airspeed_ack_t airSpeedMsg;
mavlink_msg_cmd_airspeed_ack_decode(&message,&airSpeedMsg);
break;
}
/*case MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG: only sent to UAV
{
break;
}*/
case MAVLINK_MSG_ID_FILT_ROT_VEL: // rotational velocities
{
mavlink_filt_rot_vel_t rotVelMsg;
mavlink_msg_filt_rot_vel_decode(&message,&rotVelMsg);
quint64 time = getUnixTime();
for(unsigned char i=0;i<3;i++)
{
this->m_rotVel[i]=rotVelMsg.rotVel[i];
}
emit valueChanged(uasId, "rollspeed", "rad/s", this->m_rotVel[0], time);
emit valueChanged(uasId, "pitchspeed", "rad/s", this->m_rotVel[1], time);
emit valueChanged(uasId, "yawspeed", "rad/s", this->m_rotVel[2], time);
emit attitudeSpeedChanged(uasId, this->m_rotVel[0], this->m_rotVel[1], this->m_rotVel[2], time);
break;
}
case MAVLINK_MSG_ID_LLC_OUT: // low level controller output
{
mavlink_llc_out_t llcMsg;
mavlink_msg_llc_out_decode(&message,&llcMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Servo. 1", "rad", llcMsg.servoOut[0], time);
emit valueChanged(uasId, "Servo. 2", "rad", llcMsg.servoOut[1], time);
emit valueChanged(uasId, "Servo. 3", "rad", llcMsg.servoOut[2], time);
emit valueChanged(uasId, "Servo. 4", "rad", llcMsg.servoOut[3], time);
emit valueChanged(uasId, "Motor. 1", "raw", llcMsg.MotorOut[0] , time);
emit valueChanged(uasId, "Motor. 2", "raw", llcMsg.MotorOut[1], time);
break;
}
case MAVLINK_MSG_ID_OBS_AIR_TEMP:
{
mavlink_obs_air_temp_t airTMsg;
mavlink_msg_obs_air_temp_decode(&message,&airTMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Air Temp", "", airTMsg.airT, time);
break;
}
case MAVLINK_MSG_ID_OBS_AIR_VELOCITY:
{
mavlink_obs_air_velocity_t airVMsg;
mavlink_msg_obs_air_velocity_decode(&message,&airVMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "AirVel. mag", "m/s", airVMsg.magnitude, time);
emit valueChanged(uasId, "AirVel. AoA", "rad", airVMsg.aoa, time);
emit valueChanged(uasId, "AirVel. Slip", "rad", airVMsg.slip, time);
break;
}
case MAVLINK_MSG_ID_OBS_ATTITUDE:
{
mavlink_obs_attitude_t quatMsg;
mavlink_msg_obs_attitude_decode(&message,&quatMsg);
quint64 time = getUnixTime();
this->quat2euler(quatMsg.quat,this->roll,this->pitch,this->yaw);
emit valueChanged(uasId, "roll", "rad", roll, time);
emit valueChanged(uasId, "pitch", "rad", pitch, time);
emit valueChanged(uasId, "yaw", "rad", yaw, time);
emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
emit valueChanged(uasId, "heading deg", "deg", (yaw/M_PI)*180.0, time);
emit attitudeChanged(this, roll, pitch, yaw, time);
break;
}
case MAVLINK_MSG_ID_OBS_BIAS:
{
mavlink_obs_bias_t biasMsg;
mavlink_msg_obs_bias_decode(&message, &biasMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "acc. biasX", "m/s^2", biasMsg.accBias[0], time);
emit valueChanged(uasId, "acc. biasY", "m/s^2", biasMsg.accBias[1], time);
emit valueChanged(uasId, "acc. biasZ", "m/s^2", biasMsg.accBias[2], time);
emit valueChanged(uasId, "gyro. biasX", "rad/s", biasMsg.gyroBias[0], time);
emit valueChanged(uasId, "gyro. biasY", "rad/s", biasMsg.gyroBias[1], time);
emit valueChanged(uasId, "gyro. biasZ", "rad/s", biasMsg.gyroBias[2], time);
break;
}
case MAVLINK_MSG_ID_OBS_POSITION:
{
mavlink_obs_position_t posMsg;
mavlink_msg_obs_position_decode(&message, &posMsg);
quint64 time = getUnixTime();
this->localX = posMsg.pos[0];
this->localY = posMsg.pos[1];
this->localZ = posMsg.pos[2];
emit valueChanged(uasId, "x", "m", this->localX, time);
emit valueChanged(uasId, "y", "m", this->localY, time);
emit valueChanged(uasId, "z", "m", this->localZ, time);
emit localPositionChanged(this, this->localX, this->localY, this->localZ, time);
break;
}
case MAVLINK_MSG_ID_OBS_QFF:
{
mavlink_obs_qff_t qffMsg;
mavlink_msg_obs_qff_decode(&message,&qffMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "QFF", "Pa", qffMsg.qff, time);
break;
}
case MAVLINK_MSG_ID_OBS_VELOCITY:
{
mavlink_obs_velocity_t velMsg;
mavlink_msg_obs_velocity_decode(&message, &velMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "x speed", "m/s", velMsg.vel[0], time);
emit valueChanged(uasId, "y speed", "m/s", velMsg.vel[1], time);
emit valueChanged(uasId, "z speed", "m/s", velMsg.vel[2], time);
emit speedChanged(this, velMsg.vel[0], velMsg.vel[1], velMsg.vel[2], time);
break;
}
case MAVLINK_MSG_ID_OBS_WIND:
{
mavlink_obs_wind_t windMsg;
mavlink_msg_obs_wind_decode(&message, &windMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Wind speed x", "m/s", windMsg.wind[0], time);
emit valueChanged(uasId, "Wind speed y", "m/s", windMsg.wind[1], time);
emit valueChanged(uasId, "Wind speed z", "m/s", windMsg.wind[2], time);
break;
}
case MAVLINK_MSG_ID_PM_ELEC:
{
mavlink_pm_elec_t pmMsg;
mavlink_msg_pm_elec_decode(&message, &pmMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Battery status", "%", pmMsg.BatStat, time);
emit valueChanged(uasId, "Power consuming", "W", pmMsg.PwCons, time);
emit valueChanged(uasId, "Power generating sys1", "W", pmMsg.PwGen[0], time);
emit valueChanged(uasId, "Power generating sys2", "W", pmMsg.PwGen[1], time);
emit valueChanged(uasId, "Power generating sys3", "W", pmMsg.PwGen[2], time);
break;
}
case MAVLINK_MSG_ID_SYS_STAT:
{
mavlink_sys_stat_t statMsg;
mavlink_msg_sys_stat_decode(&message,&statMsg);
quint64 time = getUnixTime();
emit valueChanged(uasId, "Motor1 status", "on/off", (statMsg.act & 0x01), time);
emit valueChanged(uasId, "Motor2 status", "on/off", (statMsg.act & 0x02), time);
emit valueChanged(uasId, "Servo1 status", "on/off", (statMsg.act & 0x04), time);
emit valueChanged(uasId, "Servo2 status", "on/off", (statMsg.act & 0x08), time);
emit valueChanged(uasId, "Servo3 status", "on/off", (statMsg.act & 0x10), time);
emit valueChanged(uasId, "Servo4 status", "on/off", (statMsg.act & 0x20), time);
emit valueChanged(uasId, "WiFI status", "on/off", (statMsg.mod & 0x01), time);
emit valueChanged(uasId, "RC status", "on/off", (statMsg.mod & 0x02), time);
emit valueChanged(uasId, "Magnetometer status", "on/off", (statMsg.mod & 0x04), time);
emit valueChanged(uasId, "Pressure status", "on/off", (statMsg.mod & 0x08), time);
emit valueChanged(uasId, "IMU acc status", "on/off", (statMsg.mod & 0x10), time);
emit valueChanged(uasId, "IMU gyro status", "on/off", (statMsg.mod & 0x20), time);
emit valueChanged(uasId, "Xbee strength", "%", statMsg.commRssi, time);
//emit valueChanged(uasId, "Xbee strength", "%", statMsg.gps, time); // TO DO: define gps bits
break;
}
default:
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
break;
}
}
}
#else
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
Q_UNUSED(link);
Q_UNUSED(message);
#endif // MAVLINK_ENABLED_SENSESOAR
}
void senseSoarMAV::quat2euler(const double *quat, double &roll, double &pitch, double &yaw)
{
roll = std::atan2(2*(quat[0]*quat[1] + quat[2]*quat[3]),quat[0]*quat[0] - quat[1]*quat[1] - quat[2]*quat[2] + quat[3]*quat[3]);
pitch = std::asin(qMax(-1.0,qMin(1.0,2*(quat[0]*quat[2] - quat[1]*quat[3]))));
yaw = std::atan2(2*(quat[1]*quat[2] + quat[0]*quat[3]),quat[0]*quat[0] + quat[1]*quat[1] - quat[2]*quat[2] - quat[3]*quat[3]);
return;
}
\ No newline at end of file
#ifndef _SENSESOARMAV_H_
#define _SENSESOARMAV_H_
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
class senseSoarMAV : public UAS
{
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
senseSoarMAV(MAVLinkProtocol* mavlink, int id);
~senseSoarMAV(void);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
protected:
float m_rotVel[3]; // Rotational velocity in the body frame
private:
void quat2euler(const double *quat, double &roll, double &pitch, double &yaw);
};
#endif // _SENSESOARMAV_H_
\ No newline at end of file
......@@ -207,19 +207,10 @@ XbeeConfigurationWindow::XbeeConfigurationWindow(LinkInterface* link, QWidget *p
baudLabel = new QLabel;
baudLabel->setText(tr("Baut Rate"));
baudBox = new QComboBox;
baudBox->addItem("1200",1200);
baudBox->addItem("2400",2400);
baudBox->addItem("4800",4800);
baudBox->addItem("9600",9600);
baudBox->addItem("19200",19200);
baudBox->addItem("38400",38400);
baudBox->addItem("57600",57600);
baudBox->setCurrentIndex(1);
baudLabel->setBuddy(baudBox);
portLabel = new QLabel;
portLabel->setText(tr("SerialPort"));
portBox = new QComboBox;
this->setupPortList();
portBox->setEditable(true);
portLabel->setBuddy(portBox);
actionLayout = new QGridLayout;
......@@ -241,6 +232,16 @@ XbeeConfigurationWindow::XbeeConfigurationWindow(LinkInterface* link, QWidget *p
connect(portBox,SIGNAL(editTextChanged(QString)),this,SLOT(setPortName(QString)));
connect(baudBox,SIGNAL(currentIndexChanged(QString)),this,SLOT(setBaudRateString(QString)));
baudBox->addItem("1200",1200);
baudBox->addItem("2400",2400);
baudBox->addItem("4800",4800);
baudBox->addItem("9600",9600);
baudBox->addItem("19200",19200);
baudBox->addItem("38400",38400);
baudBox->addItem("57600",57600);
baudBox->setCurrentIndex(6);
this->setupPortList();
portCheckTimer = new QTimer(this);
portCheckTimer->setInterval(1000);
connect(portCheckTimer, SIGNAL(timeout()), this, SLOT(setupPortList()));
......
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 2 2011, 15:51 UTC
* Generated on Friday, August 12 2011, 12:18 UTC
*/
#ifndef SENSESOAR_H
#define SENSESOAR_H
......@@ -42,10 +42,6 @@ enum SENSESOAR_MODE
// 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"
......@@ -65,7 +61,7 @@ enum SENSESOAR_MODE
// 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 }
#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, 24, 0, 12, 0, 32, 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
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 2 2011, 15:51 UTC
* Generated on Friday, August 12 2011, 12:18 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -4,7 +4,7 @@
typedef struct __mavlink_obs_attitude_t
{
float quat[4]; ///< Quaternion re;im
double quat[4]; ///< Quaternion re;im
} mavlink_obs_attitude_t;
......@@ -20,12 +20,12 @@ typedef struct __mavlink_obs_attitude_t
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* quat)
static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const double* quat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
i += put_array_by_index((const int8_t*)quat, sizeof(float)*4, i, msg->payload); // Quaternion re;im
i += put_array_by_index((const int8_t*)quat, sizeof(double)*4, i, msg->payload); // Quaternion re;im
return mavlink_finalize_message(msg, system_id, component_id, i);
}
......@@ -39,12 +39,12 @@ static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* quat)
static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const double* quat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
i += put_array_by_index((const int8_t*)quat, sizeof(float)*4, i, msg->payload); // Quaternion re;im
i += put_array_by_index((const int8_t*)quat, sizeof(double)*4, i, msg->payload); // Quaternion re;im
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
......@@ -70,7 +70,7 @@ static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const float* quat)
static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const double* quat)
{
mavlink_message_t msg;
mavlink_msg_obs_attitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, quat);
......@@ -85,11 +85,11 @@ static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const f
*
* @return Quaternion re;im
*/
static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, float* r_data)
static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, double* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*4);
return sizeof(float)*4;
memcpy(r_data, msg->payload, sizeof(double)*4);
return sizeof(double)*4;
}
/**
......
// MESSAGE SENSESOAR_MODE_ACK PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_ACK 167
typedef struct __mavlink_sensesoar_mode_ack_t
{
uint8_t mode; ///< Mode as desribed in the sensesoar_mode
uint8_t ack; ///< 0:ack, 1:nack
} mavlink_sensesoar_mode_ack_t;
/**
* @brief Pack a sensesoar_mode_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 mode Mode as desribed in the sensesoar_mode
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_ACK;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
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 sensesoar_mode_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 mode Mode as desribed in the sensesoar_mode
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_ACK;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
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 sensesoar_mode_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 sensesoar_mode_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_ack_t* sensesoar_mode_ack)
{
return mavlink_msg_sensesoar_mode_ack_pack(system_id, component_id, msg, sensesoar_mode_ack->mode, sensesoar_mode_ack->ack);
}
/**
* @brief Send a sensesoar_mode_ack message
* @param chan MAVLink channel to send the message
*
* @param mode Mode as desribed in the sensesoar_mode
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_ack_send(mavlink_channel_t chan, uint8_t mode, uint8_t ack)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, ack);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_ACK UNPACKING
/**
* @brief Get field mode from sensesoar_mode_ack message
*
* @return Mode as desribed in the sensesoar_mode
*/
static inline uint8_t mavlink_msg_sensesoar_mode_ack_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field ack from sensesoar_mode_ack message
*
* @return 0:ack, 1:nack
*/
static inline uint8_t mavlink_msg_sensesoar_mode_ack_get_ack(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a sensesoar_mode_ack message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_ack_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_ack_t* sensesoar_mode_ack)
{
sensesoar_mode_ack->mode = mavlink_msg_sensesoar_mode_ack_get_mode(msg);
sensesoar_mode_ack->ack = mavlink_msg_sensesoar_mode_ack_get_ack(msg);
}
// MESSAGE SENSESOAR_MODE_CHNG PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_CHNG 166
typedef struct __mavlink_sensesoar_mode_chng_t
{
uint8_t target; ///< Target ID
uint8_t mode; ///< Mode as desribed in the sensesoar_mode
} mavlink_sensesoar_mode_chng_t;
/**
* @brief Pack a sensesoar_mode_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 mode Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_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 mode Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_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 sensesoar_mode_chng C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_chng_t* sensesoar_mode_chng)
{
return mavlink_msg_sensesoar_mode_chng_pack(system_id, component_id, msg, sensesoar_mode_chng->target, sensesoar_mode_chng->mode);
}
/**
* @brief Send a sensesoar_mode_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param mode Mode as desribed in the sensesoar_mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_chng_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_chng_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_CHNG UNPACKING
/**
* @brief Get field target from sensesoar_mode_chng message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_sensesoar_mode_chng_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field mode from sensesoar_mode_chng message
*
* @return Mode as desribed in the sensesoar_mode
*/
static inline uint8_t mavlink_msg_sensesoar_mode_chng_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a sensesoar_mode_chng message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_chng C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_chng_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_chng_t* sensesoar_mode_chng)
{
sensesoar_mode_chng->target = mavlink_msg_sensesoar_mode_chng_get_target(msg);
sensesoar_mode_chng->mode = mavlink_msg_sensesoar_mode_chng_get_mode(msg);
}
// MESSAGE SENSESOAR_MODE_RQST PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_RQST 168
typedef struct __mavlink_sensesoar_mode_rqst_t
{
uint8_t target; ///< Target ID
} mavlink_sensesoar_mode_rqst_t;
/**
* @brief Pack a sensesoar_mode_rqst 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
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_rqst 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
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_rqst 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 sensesoar_mode_rqst C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_rqst_t* sensesoar_mode_rqst)
{
return mavlink_msg_sensesoar_mode_rqst_pack(system_id, component_id, msg, sensesoar_mode_rqst->target);
}
/**
* @brief Send a sensesoar_mode_rqst message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_rqst_send(mavlink_channel_t chan, uint8_t target)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_rqst_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_RQST UNPACKING
/**
* @brief Get field target from sensesoar_mode_rqst message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_sensesoar_mode_rqst_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Decode a sensesoar_mode_rqst message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_rqst C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_rqst_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_rqst_t* sensesoar_mode_rqst)
{
sensesoar_mode_rqst->target = mavlink_msg_sensesoar_mode_rqst_get_target(msg);
}
// MESSAGE SENSESOAR_MODE_RQST_SEND PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_RQST_SEND 169
typedef struct __mavlink_sensesoar_mode_rqst_send_t
{
uint8_t mode; ///< Mode as desribed in the sensesoar_mode
} mavlink_sensesoar_mode_rqst_send_t;
/**
* @brief Pack a sensesoar_mode_rqst_send 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 Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_send_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST_SEND;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_rqst_send 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 Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_send_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST_SEND;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_rqst_send 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 sensesoar_mode_rqst_send C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_send_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_rqst_send_t* sensesoar_mode_rqst_send)
{
return mavlink_msg_sensesoar_mode_rqst_send_pack(system_id, component_id, msg, sensesoar_mode_rqst_send->mode);
}
/**
* @brief Send a sensesoar_mode_rqst_send message
* @param chan MAVLink channel to send the message
*
* @param mode Mode as desribed in the sensesoar_mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_rqst_send_send(mavlink_channel_t chan, uint8_t mode)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_rqst_send_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_RQST_SEND UNPACKING
/**
* @brief Get field mode from sensesoar_mode_rqst_send message
*
* @return Mode as desribed in the sensesoar_mode
*/
static inline uint8_t mavlink_msg_sensesoar_mode_rqst_send_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Decode a sensesoar_mode_rqst_send message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_rqst_send C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_rqst_send_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_rqst_send_t* sensesoar_mode_rqst_send)
{
sensesoar_mode_rqst_send->mode = mavlink_msg_sensesoar_mode_rqst_send_get_mode(msg);
}
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 2 2011, 15:51 UTC
* Generated on Friday, August 12 2011, 12:18 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 2 2011, 15:51 UTC
* Generated on Friday, August 12 2011, 12:18 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -10,24 +10,6 @@
</enum>
</enums>
<messages>
<message id="166" name="SENSESOAR_MODE_CHNG">
change flight mode of the sensesoar
<field type="uint8_t" name="target">Target ID</field>
<field type="uint8_t" name="mode">Mode as desribed in the sensesoar_mode</field>
</message>
<message id="167" name="SENSESOAR_MODE_ACK">
accept change of mode
<field type="uint8_t" name="mode">Mode as desribed in the sensesoar_mode</field>
<field type="uint8_t" name="ack">0:ack, 1:nack</field>
</message>
<message id="168" name="SENSESOAR_MODE_RQST">
request for sending current flight mode
<field type="uint8_t" name="target">Target ID</field>
</message>
<message id="169" name="SENSESOAR_MODE_RQST_SEND">
sending current flight mode
<field type="uint8_t" name="mode">Mode as desribed in the sensesoar_mode</field>
</message>
<message id="170" name="OBS_POSITION">
Position estimate of the observer in NED inertial frame
<field type="double[3]" name="pos">Position</field>
......@@ -38,7 +20,7 @@
</message>
<message id="174" name="OBS_ATTITUDE">
attitude estimate of the observer
<field type="float[4]" name="quat">Quaternion re;im</field>
<field type="double[4]" name="quat">Quaternion re;im</field>
</message>
<message id="176" name="OBS_WIND">
Wind estimate in NED inertial frame
......
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