16 changed files with 269 additions and 484 deletions
@ -0,0 +1,205 @@
@@ -0,0 +1,205 @@
|
||||
#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; |
||||
} |
@ -0,0 +1,28 @@
@@ -0,0 +1,28 @@
|
||||
#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_
|
@ -1,118 +0,0 @@
@@ -1,118 +0,0 @@
|
||||
// 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); |
||||
} |
@ -1,118 +0,0 @@
@@ -1,118 +0,0 @@
|
||||
// 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); |
||||
} |
@ -1,101 +0,0 @@
@@ -1,101 +0,0 @@
|
||||
// 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); |
||||
} |
@ -1,101 +0,0 @@
@@ -1,101 +0,0 @@
|
||||
// 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); |
||||
} |
Loading…
Reference in new issue