Commit 685e048b authored by lm's avatar lm

Merge branch 'v10release' of github.com:pixhawk/qgroundcontrol into v10release

parents 94a062f4 411875fd
...@@ -221,7 +221,7 @@ message("Compiling for linux 32") ...@@ -221,7 +221,7 @@ message("Compiling for linux 32")
DEFINES += QGC_LIBFREENECT_ENABLED DEFINES += QGC_LIBFREENECT_ENABLED
} }
QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
...@@ -295,7 +295,7 @@ linux-g++-64 { ...@@ -295,7 +295,7 @@ linux-g++-64 {
DEFINES += QGC_LIBFREENECT_ENABLED DEFINES += QGC_LIBFREENECT_ENABLED
} }
QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
......
...@@ -758,7 +758,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -758,7 +758,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) { for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
if (j != 5) { if (j != 5) {
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), 0, onboardParams.size(), j); mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), MAVLINK_TYPE_FLOAT, onboardParams.size(), j);
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -786,7 +786,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -786,7 +786,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value); onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, 0, onboardParams.size(), onboardParams.keys().indexOf(key)); mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -807,7 +807,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -807,7 +807,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key)); mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -819,7 +819,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -819,7 +819,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key)); mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
......
...@@ -350,8 +350,8 @@ fgScenery = "--fg-scenery=/Applications/FlightGear.app/Contents/Resources/data/S ...@@ -350,8 +350,8 @@ fgScenery = "--fg-scenery=/Applications/FlightGear.app/Contents/Resources/data/S
#endif #endif
#ifdef Q_OS_WIN32 #ifdef Q_OS_WIN32
processFgfs = "C:\Program Files (x86)\FlightGear\bin\Win32\fgfs"; processFgfs = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs";
fgRoot = "--fg-root=C:\Program Files (x86)\FlightGear\data"; fgRoot = "--fg-root=C:\\Program Files (x86)\\FlightGear\\data";
#endif #endif
#ifdef Q_OS_LINUX #ifdef Q_OS_LINUX
...@@ -361,10 +361,9 @@ fgRoot = "--fg-root=/usr/share/flightgear/data"; ...@@ -361,10 +361,9 @@ fgRoot = "--fg-root=/usr/share/flightgear/data";
processCall << fgRoot; processCall << fgRoot;
processCall << fgScenery; processCall << fgScenery;
processCall << "--generic=socket,out,50,127.0.0.1,49005,udp,ardupilot"; processCall << "--generic=socket,out,50,127.0.0.1,49005,udp,qgroundcontrol";
processCall << "--generic=socket,in,50,127.0.0.1,49000,udp,ardupilot"; processCall << "--generic=socket,in,50,127.0.0.1,49000,udp,qgroundcontrol";
processCall << "--in-air"; processCall << "--in-air";
processCall << "--altitude=10";
processCall << "--vc=90"; processCall << "--vc=90";
processCall << "--heading=300"; processCall << "--heading=300";
processCall << "--timeofday=noon"; processCall << "--timeofday=noon";
...@@ -386,8 +385,9 @@ if (mav->getSystemType() == MAV_TYPE_QUADROTOR) ...@@ -386,8 +385,9 @@ if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
processCall << "--prop:/engines/engine[2]/running=true"; processCall << "--prop:/engines/engine[2]/running=true";
processCall << "--prop:/engines/engine[3]/running=true"; processCall << "--prop:/engines/engine[3]/running=true";
} }
processCall << QString("--lat=%1").arg(mav->getLatitude()); processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
processCall << QString("--lon=%1").arg(mav->getLongitude()); processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
// Add new argument with this: processCall << ""; // Add new argument with this: processCall << "";
processCall << QString("--aircraft=%2").arg(aircraft); processCall << QString("--aircraft=%2").arg(aircraft);
......
...@@ -658,6 +658,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -658,6 +658,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
int component = message.compid; int component = message.compid;
mavlink_param_union_t val; mavlink_param_union_t val;
val.param_float = value.param_value; val.param_float = value.param_value;
val.type = value.param_type;
// Convert to machine order if necessary // Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP //#if MAVLINK_NEED_BYTE_SWAP
...@@ -680,22 +681,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -680,22 +681,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
switch (value.param_type) switch (value.param_type)
{ {
case MAVLINK_TYPE_FLOAT: case MAVLINK_TYPE_FLOAT:
parameters.value(component)->insert(parameterName, val.param_float); {
// Variant
QVariant param(val.param_float);
parameters.value(component)->insert(parameterName, param);
// Emit change // Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_float); emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float); emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param;
}
break; break;
case MAVLINK_TYPE_UINT32_T: case MAVLINK_TYPE_UINT32_T:
parameters.value(component)->insert(parameterName, val.param_uint32); {
// Variant
QVariant param(val.param_uint32);
parameters.value(component)->insert(parameterName, param);
// Emit change // Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_uint32); emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32); emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param;
}
break; break;
case MAVLINK_TYPE_INT32_T: case MAVLINK_TYPE_INT32_T:
parameters.value(component)->insert(parameterName, val.param_int32); {
// Variant
QVariant param(val.param_int32);
parameters.value(component)->insert(parameterName, param);
// Emit change // Emit change
emit parameterChanged(uasId, message.compid, parameterName, val.param_int32); emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32); emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param;
}
break; break;
default: default:
qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type; qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
...@@ -1860,6 +1876,8 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v ...@@ -1860,6 +1876,8 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
p.target_system = (uint8_t)uasId; p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component; p.target_component = (uint8_t)component;
qDebug() << "SENT PARAM:" << value;
// Copy string into buffer, ensuring not to exceed the buffer size // Copy string into buffer, ensuring not to exceed the buffer size
for (unsigned int i = 0; i < sizeof(p.param_id); i++) for (unsigned int i = 0; i < sizeof(p.param_id); i++)
{ {
......
This diff is collapsed.
...@@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text) ...@@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text)
if (text.compare("Global") == 0) { if (text.compare("Global") == 0) {
frame = MAV_FRAME_GLOBAL; frame = MAV_FRAME_GLOBAL;
} else if (text.compare("Local") == 0) { } else if (text.compare("Local") == 0) {
frame = MAV_FRAME_LOCAL; frame = MAV_FRAME_LOCAL_NED;
} }
getPosition(lastRobotX, lastRobotY, lastRobotZ); getPosition(lastRobotX, lastRobotY, lastRobotZ);
...@@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void) ...@@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void)
getGlobalCursorPosition(getMouseX(), getMouseY(), altitude); getGlobalCursorPosition(getMouseX(), getMouseY(), altitude);
target.set(cursorWorldCoords.first, cursorWorldCoords.second); target.set(cursorWorldCoords.first, cursorWorldCoords.second);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ(); double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
...@@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void) ...@@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void)
latitude, longitude); latitude, longitude);
wp = new Waypoint(0, longitude, latitude, altitude); wp = new Waypoint(0, longitude, latitude, altitude);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ(); double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
...@@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void) ...@@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void)
waypoint->setX(longitude); waypoint->setX(longitude);
waypoint->setY(latitude); waypoint->setY(latitude);
waypoint->setZ(altitude); waypoint->setZ(altitude);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ(); double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
...@@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) ...@@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
Waypoint* waypoint = waypoints.at(selectedWpIndex); Waypoint* waypoint = waypoints.at(selectedWpIndex);
double altitude = waypoint->getZ(); double altitude = waypoint->getZ();
if (frame == MAV_FRAME_LOCAL) { if (frame == MAV_FRAME_LOCAL_NED) {
altitude = -altitude; altitude = -altitude;
} }
...@@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) ...@@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
if (ok) { if (ok) {
if (frame == MAV_FRAME_GLOBAL) { if (frame == MAV_FRAME_GLOBAL) {
waypoint->setZ(newAltitude); waypoint->setZ(newAltitude);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
waypoint->setZ(-newAltitude); waypoint->setZ(-newAltitude);
} }
} }
...@@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z, ...@@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z,
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude; z = -altitude;
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
x = uas->getLocalX(); x = uas->getLocalX();
y = uas->getLocalY(); y = uas->getLocalY();
z = uas->getLocalZ(); z = uas->getLocalZ();
...@@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z, ...@@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z,
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude; z = -altitude;
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
x = uas->getLocalX(); x = uas->getLocalX();
y = uas->getLocalY(); y = uas->getLocalY();
z = uas->getLocalZ(); z = uas->getLocalZ();
...@@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ, ...@@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ,
oss.precision(6); oss.precision(6);
oss << " Cursor [" << cursorLatitude << oss << " Cursor [" << cursorLatitude <<
" " << cursorLongitude << "]"; " " << cursorLongitude << "]";
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
oss << " x = " << robotX << oss << " x = " << robotX <<
" y = " << robotY << " y = " << robotY <<
" z = " << robotZ << " z = " << robotZ <<
......
...@@ -461,7 +461,7 @@ QVariant QGCGoogleEarthView::documentElement(QString name) ...@@ -461,7 +461,7 @@ QVariant QGCGoogleEarthView::documentElement(QString name)
name.prepend("JScript_"); name.prepend("JScript_");
HRESULT res = doc->getElementById(QStringToBSTR(name), &element); HRESULT res = doc->getElementById(QStringToBSTR(name), &element);
//BSTR elemString; //BSTR elemString;
if (element) { if (SUCCEEDED(res) && element) {
//element->get_innerHTML(&elemString); //element->get_innerHTML(&elemString);
VARIANT var; VARIANT var;
var.vt = VT_BSTR; var.vt = VT_BSTR;
......
...@@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas) ...@@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
QString utmZone; QString utmZone;
Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone); Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
robotZ = -altitude; robotZ = -altitude;
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
robotX = uas->getLocalX(); robotX = uas->getLocalX();
robotY = uas->getLocalY(); robotY = uas->getLocalY();
robotZ = uas->getLocalZ(); robotZ = uas->getLocalZ();
...@@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z) ...@@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z)
QString utmZone; QString utmZone;
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude; z = -altitude;
} else if (wp->getFrame() == MAV_FRAME_LOCAL) { } else if (wp->getFrame() == MAV_FRAME_LOCAL_NED) {
x = wp->getX(); x = wp->getX();
y = wp->getY(); y = wp->getY();
z = wp->getZ(); z = wp->getZ();
......
...@@ -44,14 +44,27 @@ typedef struct __mavlink_set_mag_offsets_t ...@@ -44,14 +44,27 @@ typedef struct __mavlink_set_mag_offsets_t
static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{ {
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
put_int16_t_by_index(msg, 0, mag_ofs_x); // magnetometer X offset _mav_put_int16_t(buf, 0, mag_ofs_x);
put_int16_t_by_index(msg, 2, mag_ofs_y); // magnetometer Y offset _mav_put_int16_t(buf, 2, mag_ofs_y);
put_int16_t_by_index(msg, 4, mag_ofs_z); // magnetometer Z offset _mav_put_int16_t(buf, 4, mag_ofs_z);
put_uint8_t_by_index(msg, 6, target_system); // System ID _mav_put_uint8_t(buf, 6, target_system);
put_uint8_t_by_index(msg, 7, target_component); // Component ID _mav_put_uint8_t(buf, 7, target_component);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, 8, 219); return mavlink_finalize_message(msg, system_id, component_id, 8, 219);
} }
...@@ -72,14 +85,27 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, ...@@ -72,14 +85,27 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id,
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z) uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z)
{ {
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
put_int16_t_by_index(msg, 0, mag_ofs_x); // magnetometer X offset _mav_put_int16_t(buf, 0, mag_ofs_x);
put_int16_t_by_index(msg, 2, mag_ofs_y); // magnetometer Y offset _mav_put_int16_t(buf, 2, mag_ofs_y);
put_int16_t_by_index(msg, 4, mag_ofs_z); // magnetometer Z offset _mav_put_int16_t(buf, 4, mag_ofs_z);
put_uint8_t_by_index(msg, 6, target_system); // System ID _mav_put_uint8_t(buf, 6, target_system);
put_uint8_t_by_index(msg, 7, target_component); // Component ID _mav_put_uint8_t(buf, 7, target_component);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 219); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 219);
} }
...@@ -110,16 +136,25 @@ static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uin ...@@ -110,16 +136,25 @@ static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uin
static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 8); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
put_int16_t_by_index(msg, 0, mag_ofs_x); // magnetometer X offset _mav_put_int16_t(buf, 2, mag_ofs_y);
put_int16_t_by_index(msg, 2, mag_ofs_y); // magnetometer Y offset _mav_put_int16_t(buf, 4, mag_ofs_z);
put_int16_t_by_index(msg, 4, mag_ofs_z); // magnetometer Z offset _mav_put_uint8_t(buf, 6, target_system);
put_uint8_t_by_index(msg, 6, target_system); // System ID _mav_put_uint8_t(buf, 7, target_component);
put_uint8_t_by_index(msg, 7, target_component); // Component ID
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 8, 219);
mavlink_finalize_message_chan_send(msg, chan, 8, 219); #else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, 8, 219);
#endif
} }
#endif #endif
...@@ -134,7 +169,7 @@ static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint ...@@ -134,7 +169,7 @@ static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint
*/ */
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 6); return _MAV_RETURN_uint8_t(msg, 6);
} }
/** /**
...@@ -144,7 +179,7 @@ static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlin ...@@ -144,7 +179,7 @@ static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlin
*/ */
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 7); return _MAV_RETURN_uint8_t(msg, 7);
} }
/** /**
...@@ -154,7 +189,7 @@ static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mav ...@@ -154,7 +189,7 @@ static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mav
*/ */
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg) static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 0); return _MAV_RETURN_int16_t(msg, 0);
} }
/** /**
...@@ -164,7 +199,7 @@ static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_me ...@@ -164,7 +199,7 @@ static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_me
*/ */
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg) static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 2); return _MAV_RETURN_int16_t(msg, 2);
} }
/** /**
...@@ -174,7 +209,7 @@ static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_me ...@@ -174,7 +209,7 @@ static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_me
*/ */
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg) static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 4); return _MAV_RETURN_int16_t(msg, 4);
} }
/** /**
...@@ -192,6 +227,6 @@ static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* m ...@@ -192,6 +227,6 @@ static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* m
set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg); set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg); set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
#else #else
memcpy(set_mag_offsets, MAVLINK_PAYLOAD(msg), 8); memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8);
#endif #endif
} }
...@@ -11,25 +11,25 @@ extern "C" { ...@@ -11,25 +11,25 @@ extern "C" {
#ifndef MAVLINK_TEST_ALL #ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL #define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t); static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_ardupilotmega(uint8_t, uint8_t); static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_all(uint8_t system_id, uint8_t component_id) static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_test_common(system_id, component_id); mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_ardupilotmega(system_id, component_id); mavlink_test_ardupilotmega(system_id, component_id, last_msg);
} }
#endif #endif
#include "../common/testsuite.h" #include "../common/testsuite.h"
static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id) static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_message_t msg; mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i; uint16_t i;
mavlink_sensor_offsets_t packet2, packet1 = { mavlink_sensor_offsets_t packet_in = {
17.0, 17.0,
963497672, 963497672,
963497880, 963497880,
...@@ -43,52 +43,107 @@ static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id) ...@@ -43,52 +43,107 @@ static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id)
19211, 19211,
19315, 19315,
}; };
if (sizeof(packet2) != 42) { mavlink_sensor_offsets_t packet1, packet2;
packet2 = packet1; // cope with alignment within the packet memset(&packet1, 0, sizeof(packet1));
} packet1.mag_declination = packet_in.mag_declination;
packet1.raw_press = packet_in.raw_press;
packet1.raw_temp = packet_in.raw_temp;
packet1.gyro_cal_x = packet_in.gyro_cal_x;
packet1.gyro_cal_y = packet_in.gyro_cal_y;
packet1.gyro_cal_z = packet_in.gyro_cal_z;
packet1.accel_cal_x = packet_in.accel_cal_x;
packet1.accel_cal_y = packet_in.accel_cal_y;
packet1.accel_cal_z = packet_in.accel_cal_z;
packet1.mag_ofs_x = packet_in.mag_ofs_x;
packet1.mag_ofs_y = packet_in.mag_ofs_y;
packet1.mag_ofs_z = packet_in.mag_ofs_z;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1); mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sensor_offsets_decode(&msg, &packet2); mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg); mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) { for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]); comm_send_ch(MAVLINK_COMM_0, buffer[i]);
} }
mavlink_msg_sensor_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_send(MAVLINK_COMM_1 , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); mavlink_msg_sensor_offsets_send(MAVLINK_COMM_1 , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id) static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_message_t msg; mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i; uint16_t i;
mavlink_set_mag_offsets_t packet2, packet1 = { mavlink_set_mag_offsets_t packet_in = {
17235, 17235,
17339, 17339,
17443, 17443,
151, 151,
218, 218,
}; };
if (sizeof(packet2) != 8) { mavlink_set_mag_offsets_t packet1, packet2;
packet2 = packet1; // cope with alignment within the packet memset(&packet1, 0, sizeof(packet1));
} packet1.mag_ofs_x = packet_in.mag_ofs_x;
packet1.mag_ofs_y = packet_in.mag_ofs_y;
packet1.mag_ofs_z = packet_in.mag_ofs_z;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_encode(system_id, component_id, &msg, &packet1); mavlink_msg_set_mag_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_mag_offsets_decode(&msg, &packet2); mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z ); mavlink_msg_set_mag_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z ); mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg); mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) { for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]); comm_send_ch(MAVLINK_COMM_0, buffer[i]);
} }
mavlink_msg_set_mag_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z ); mavlink_msg_set_mag_offsets_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id) static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_test_sensor_offsets(system_id, component_id); mavlink_test_sensor_offsets(system_id, component_id, last_msg);
mavlink_test_set_mag_offsets(system_id, component_id); mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
} }
#ifdef __cplusplus #ifdef __cplusplus
......
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Aug 29 10:37:55 2011" #define MAVLINK_BUILD_DATE "Wed Aug 31 10:19:04 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h" #include "mavlink.h"
......
...@@ -64,6 +64,23 @@ static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) ...@@ -64,6 +64,23 @@ static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length)
return crcTmp; return crcTmp;
} }
/**
* @brief Accumulate the X.25 CRC by adding an array of bytes
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
crc_accumulate(*p++, crcAccum);
}
}
......
This diff is collapsed.
...@@ -50,16 +50,31 @@ typedef struct __mavlink_attitude_t ...@@ -50,16 +50,31 @@ typedef struct __mavlink_attitude_t
static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{ {
msg->msgid = MAVLINK_MSG_ID_ATTITUDE; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, rollspeed);
_mav_put_float(buf, 20, pitchspeed);
_mav_put_float(buf, 24, yawspeed);
memcpy(_MAV_PAYLOAD(msg), buf, 28);
#else
mavlink_attitude_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) memcpy(_MAV_PAYLOAD(msg), &packet, 28);
put_float_by_index(msg, 4, roll); // Roll angle (rad) #endif
put_float_by_index(msg, 8, pitch); // Pitch angle (rad)
put_float_by_index(msg, 12, yaw); // Yaw angle (rad)
put_float_by_index(msg, 16, rollspeed); // Roll angular speed (rad/s)
put_float_by_index(msg, 20, pitchspeed); // Pitch angular speed (rad/s)
put_float_by_index(msg, 24, yawspeed); // Yaw angular speed (rad/s)
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, 28, 39); return mavlink_finalize_message(msg, system_id, component_id, 28, 39);
} }
...@@ -82,16 +97,31 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t ...@@ -82,16 +97,31 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t
mavlink_message_t* msg, mavlink_message_t* msg,
uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
{ {
msg->msgid = MAVLINK_MSG_ID_ATTITUDE; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, rollspeed);
_mav_put_float(buf, 20, pitchspeed);
_mav_put_float(buf, 24, yawspeed);
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) memcpy(_MAV_PAYLOAD(msg), buf, 28);
put_float_by_index(msg, 4, roll); // Roll angle (rad) #else
put_float_by_index(msg, 8, pitch); // Pitch angle (rad) mavlink_attitude_t packet;
put_float_by_index(msg, 12, yaw); // Yaw angle (rad) packet.time_boot_ms = time_boot_ms;
put_float_by_index(msg, 16, rollspeed); // Roll angular speed (rad/s) packet.roll = roll;
put_float_by_index(msg, 20, pitchspeed); // Pitch angular speed (rad/s) packet.pitch = pitch;
put_float_by_index(msg, 24, yawspeed); // Yaw angular speed (rad/s) packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
memcpy(_MAV_PAYLOAD(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 39); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 39);
} }
...@@ -124,18 +154,29 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co ...@@ -124,18 +154,29 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 28); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_ATTITUDE; char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, rollspeed);
_mav_put_float(buf, 20, pitchspeed);
_mav_put_float(buf, 24, yawspeed);
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, 28, 39);
put_float_by_index(msg, 4, roll); // Roll angle (rad) #else
put_float_by_index(msg, 8, pitch); // Pitch angle (rad) mavlink_attitude_t packet;
put_float_by_index(msg, 12, yaw); // Yaw angle (rad) packet.time_boot_ms = time_boot_ms;
put_float_by_index(msg, 16, rollspeed); // Roll angular speed (rad/s) packet.roll = roll;
put_float_by_index(msg, 20, pitchspeed); // Pitch angular speed (rad/s) packet.pitch = pitch;
put_float_by_index(msg, 24, yawspeed); // Yaw angular speed (rad/s) packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mavlink_finalize_message_chan_send(msg, chan, 28, 39); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, 28, 39);
#endif
} }
#endif #endif
...@@ -150,7 +191,7 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t ti ...@@ -150,7 +191,7 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t ti
*/ */
static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint32_t(msg, 0); return _MAV_RETURN_uint32_t(msg, 0);
} }
/** /**
...@@ -160,7 +201,7 @@ static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_messa ...@@ -160,7 +201,7 @@ static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_messa
*/ */
static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 4); return _MAV_RETURN_float(msg, 4);
} }
/** /**
...@@ -170,7 +211,7 @@ static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) ...@@ -170,7 +211,7 @@ static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
*/ */
static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 8); return _MAV_RETURN_float(msg, 8);
} }
/** /**
...@@ -180,7 +221,7 @@ static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) ...@@ -180,7 +221,7 @@ static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
*/ */
static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 12); return _MAV_RETURN_float(msg, 12);
} }
/** /**
...@@ -190,7 +231,7 @@ static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) ...@@ -190,7 +231,7 @@ static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
*/ */
static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 16); return _MAV_RETURN_float(msg, 16);
} }
/** /**
...@@ -200,7 +241,7 @@ static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* ...@@ -200,7 +241,7 @@ static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t*
*/ */
static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 20); return _MAV_RETURN_float(msg, 20);
} }
/** /**
...@@ -210,7 +251,7 @@ static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* ...@@ -210,7 +251,7 @@ static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t*
*/ */
static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 24); return _MAV_RETURN_float(msg, 24);
} }
/** /**
...@@ -230,6 +271,6 @@ static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mav ...@@ -230,6 +271,6 @@ static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mav
attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
#else #else
memcpy(attitude, MAVLINK_PAYLOAD(msg), 28); memcpy(attitude, _MAV_PAYLOAD(msg), 28);
#endif #endif
} }
...@@ -32,10 +32,19 @@ typedef struct __mavlink_auth_key_t ...@@ -32,10 +32,19 @@ typedef struct __mavlink_auth_key_t
static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *key) const char *key)
{ {
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_auth_key_t packet;
put_char_array_by_index(msg, 0, key, 32); // key memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
return mavlink_finalize_message(msg, system_id, component_id, 32, 119); return mavlink_finalize_message(msg, system_id, component_id, 32, 119);
} }
...@@ -52,10 +61,19 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t ...@@ -52,10 +61,19 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t
mavlink_message_t* msg, mavlink_message_t* msg,
const char *key) const char *key)
{ {
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
put_char_array_by_index(msg, 0, key, 32); // key _mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_auth_key_t packet;
memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119);
} }
...@@ -82,12 +100,17 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co ...@@ -82,12 +100,17 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co
static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 32); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; char buf[32];
put_char_array_by_index(msg, 0, key, 32); // key _mav_put_char_array(buf, 0, key, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, 32, 119);
#else
mavlink_auth_key_t packet;
mavlink_finalize_message_chan_send(msg, chan, 32, 119); memcpy(packet.key, key, sizeof(char)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, 32, 119);
#endif
} }
#endif #endif
...@@ -102,7 +125,7 @@ static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char ...@@ -102,7 +125,7 @@ static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char
*/ */
static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
{ {
return MAVLINK_MSG_RETURN_char_array(msg, key, 32, 0); return _MAV_RETURN_char_array(msg, key, 32, 0);
} }
/** /**
...@@ -116,6 +139,6 @@ static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mav ...@@ -116,6 +139,6 @@ static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mav
#if MAVLINK_NEED_BYTE_SWAP #if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_auth_key_get_key(msg, auth_key->key); mavlink_msg_auth_key_get_key(msg, auth_key->key);
#else #else
memcpy(auth_key, MAVLINK_PAYLOAD(msg), 32); memcpy(auth_key, _MAV_PAYLOAD(msg), 32);
#endif #endif
} }
...@@ -41,13 +41,23 @@ typedef struct __mavlink_change_operator_control_t ...@@ -41,13 +41,23 @@ typedef struct __mavlink_change_operator_control_t
static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
{ {
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
put_uint8_t_by_index(msg, 0, target_system); // System the GCS requests control for _mav_put_uint8_t(buf, 0, target_system);
put_uint8_t_by_index(msg, 1, control_request); // 0: request control of this MAV, 1: Release control of this MAV _mav_put_uint8_t(buf, 1, control_request);
put_uint8_t_by_index(msg, 2, version); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. _mav_put_uint8_t(buf, 2, version);
put_char_array_by_index(msg, 3, passkey, 25); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" _mav_put_char_array(buf, 3, passkey, 25);
memcpy(_MAV_PAYLOAD(msg), buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
memcpy(packet.passkey, passkey, sizeof(char)*25);
memcpy(_MAV_PAYLOAD(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 28, 217); return mavlink_finalize_message(msg, system_id, component_id, 28, 217);
} }
...@@ -67,13 +77,23 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys ...@@ -67,13 +77,23 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey)
{ {
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
put_uint8_t_by_index(msg, 0, target_system); // System the GCS requests control for _mav_put_uint8_t(buf, 0, target_system);
put_uint8_t_by_index(msg, 1, control_request); // 0: request control of this MAV, 1: Release control of this MAV _mav_put_uint8_t(buf, 1, control_request);
put_uint8_t_by_index(msg, 2, version); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. _mav_put_uint8_t(buf, 2, version);
put_char_array_by_index(msg, 3, passkey, 25); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" _mav_put_char_array(buf, 3, passkey, 25);
memcpy(_MAV_PAYLOAD(msg), buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
memcpy(packet.passkey, passkey, sizeof(char)*25);
memcpy(_MAV_PAYLOAD(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 217); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 217);
} }
...@@ -103,15 +123,21 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system ...@@ -103,15 +123,21 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system
static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 28); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
put_uint8_t_by_index(msg, 0, target_system); // System the GCS requests control for _mav_put_uint8_t(buf, 1, control_request);
put_uint8_t_by_index(msg, 1, control_request); // 0: request control of this MAV, 1: Release control of this MAV _mav_put_uint8_t(buf, 2, version);
put_uint8_t_by_index(msg, 2, version); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. _mav_put_char_array(buf, 3, passkey, 25);
put_char_array_by_index(msg, 3, passkey, 25); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28, 217);
#else
mavlink_finalize_message_chan_send(msg, chan, 28, 217); mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
memcpy(packet.passkey, passkey, sizeof(char)*25);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28, 217);
#endif
} }
#endif #endif
...@@ -126,7 +152,7 @@ static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t ch ...@@ -126,7 +152,7 @@ static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t ch
*/ */
static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 0); return _MAV_RETURN_uint8_t(msg, 0);
} }
/** /**
...@@ -136,7 +162,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_target_system(cons ...@@ -136,7 +162,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_target_system(cons
*/ */
static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 1); return _MAV_RETURN_uint8_t(msg, 1);
} }
/** /**
...@@ -146,7 +172,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_control_request(co ...@@ -146,7 +172,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_control_request(co
*/ */
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 2); return _MAV_RETURN_uint8_t(msg, 2);
} }
/** /**
...@@ -156,7 +182,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavl ...@@ -156,7 +182,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavl
*/ */
static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey)
{ {
return MAVLINK_MSG_RETURN_char_array(msg, passkey, 25, 3); return _MAV_RETURN_char_array(msg, passkey, 25, 3);
} }
/** /**
...@@ -173,6 +199,6 @@ static inline void mavlink_msg_change_operator_control_decode(const mavlink_mess ...@@ -173,6 +199,6 @@ static inline void mavlink_msg_change_operator_control_decode(const mavlink_mess
change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
#else #else
memcpy(change_operator_control, MAVLINK_PAYLOAD(msg), 28); memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28);
#endif #endif
} }
...@@ -38,12 +38,23 @@ typedef struct __mavlink_change_operator_control_ack_t ...@@ -38,12 +38,23 @@ typedef struct __mavlink_change_operator_control_ack_t
static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{ {
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
put_uint8_t_by_index(msg, 0, gcs_system_id); // ID of the GCS this message memcpy(_MAV_PAYLOAD(msg), &packet, 3);
put_uint8_t_by_index(msg, 1, control_request); // 0: request control of this MAV, 1: Release control of this MAV #endif
put_uint8_t_by_index(msg, 2, ack); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 3, 104); return mavlink_finalize_message(msg, system_id, component_id, 3, 104);
} }
...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t ...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) uint8_t gcs_system_id,uint8_t control_request,uint8_t ack)
{ {
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
put_uint8_t_by_index(msg, 0, gcs_system_id); // ID of the GCS this message memcpy(_MAV_PAYLOAD(msg), buf, 3);
put_uint8_t_by_index(msg, 1, control_request); // 0: request control of this MAV, 1: Release control of this MAV #else
put_uint8_t_by_index(msg, 2, ack); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104);
} }
...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy ...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy
static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 3); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
put_uint8_t_by_index(msg, 0, gcs_system_id); // ID of the GCS this message _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, 3, 104);
put_uint8_t_by_index(msg, 1, control_request); // 0: request control of this MAV, 1: Release control of this MAV #else
put_uint8_t_by_index(msg, 2, ack); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
mavlink_finalize_message_chan_send(msg, chan, 3, 104); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, 3, 104);
#endif
} }
#endif #endif
...@@ -118,7 +147,7 @@ static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_ ...@@ -118,7 +147,7 @@ static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_
*/ */
static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 0); return _MAV_RETURN_uint8_t(msg, 0);
} }
/** /**
...@@ -128,7 +157,7 @@ static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id( ...@@ -128,7 +157,7 @@ static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(
*/ */
static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 1); return _MAV_RETURN_uint8_t(msg, 1);
} }
/** /**
...@@ -138,7 +167,7 @@ static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_reques ...@@ -138,7 +167,7 @@ static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_reques
*/ */
static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 2); return _MAV_RETURN_uint8_t(msg, 2);
} }
/** /**
...@@ -154,6 +183,6 @@ static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_ ...@@ -154,6 +183,6 @@ static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_
change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg);
change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg);
#else #else
memcpy(change_operator_control_ack, MAVLINK_PAYLOAD(msg), 3); memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), 3);
#endif #endif
} }
...@@ -35,11 +35,21 @@ typedef struct __mavlink_command_ack_t ...@@ -35,11 +35,21 @@ typedef struct __mavlink_command_ack_t
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float command, float result) float command, float result)
{ {
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
put_float_by_index(msg, 0, command); // Current airspeed in m/s memcpy(_MAV_PAYLOAD(msg), &packet, 8);
put_float_by_index(msg, 4, result); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION #endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 8, 8); return mavlink_finalize_message(msg, system_id, component_id, 8, 8);
} }
...@@ -57,11 +67,21 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint ...@@ -57,11 +67,21 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint
mavlink_message_t* msg, mavlink_message_t* msg,
float command,float result) float command,float result)
{ {
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
put_float_by_index(msg, 0, command); // Current airspeed in m/s memcpy(_MAV_PAYLOAD(msg), buf, 8);
put_float_by_index(msg, 4, result); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION #else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 8); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 8);
} }
...@@ -89,13 +109,19 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t ...@@ -89,13 +109,19 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result) static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 8); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
put_float_by_index(msg, 0, command); // Current airspeed in m/s _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 8, 8);
put_float_by_index(msg, 4, result); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION #else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
mavlink_finalize_message_chan_send(msg, chan, 8, 8); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 8, 8);
#endif
} }
#endif #endif
...@@ -110,7 +136,7 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float co ...@@ -110,7 +136,7 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float co
*/ */
static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 0); return _MAV_RETURN_float(msg, 0);
} }
/** /**
...@@ -120,7 +146,7 @@ static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* ...@@ -120,7 +146,7 @@ static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t*
*/ */
static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 4); return _MAV_RETURN_float(msg, 4);
} }
/** /**
...@@ -135,6 +161,6 @@ static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, ...@@ -135,6 +161,6 @@ static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg,
command_ack->command = mavlink_msg_command_ack_get_command(msg); command_ack->command = mavlink_msg_command_ack_get_command(msg);
command_ack->result = mavlink_msg_command_ack_get_result(msg); command_ack->result = mavlink_msg_command_ack_get_result(msg);
#else #else
memcpy(command_ack, MAVLINK_PAYLOAD(msg), 8); memcpy(command_ack, _MAV_PAYLOAD(msg), 8);
#endif #endif
} }
...@@ -53,17 +53,33 @@ typedef struct __mavlink_command_short_t ...@@ -53,17 +53,33 @@ typedef struct __mavlink_command_short_t
static inline uint16_t mavlink_msg_command_short_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_command_short_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{ {
msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
_mav_put_uint8_t(buf, 18, command);
_mav_put_uint8_t(buf, 19, confirmation);
memcpy(_MAV_PAYLOAD(msg), buf, 20);
#else
mavlink_command_short_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command = command;
packet.confirmation = confirmation;
put_float_by_index(msg, 0, param1); // Parameter 1, as defined by MAV_CMD enum. memcpy(_MAV_PAYLOAD(msg), &packet, 20);
put_float_by_index(msg, 4, param2); // Parameter 2, as defined by MAV_CMD enum. #endif
put_float_by_index(msg, 8, param3); // Parameter 3, as defined by MAV_CMD enum.
put_float_by_index(msg, 12, param4); // Parameter 4, as defined by MAV_CMD enum.
put_uint8_t_by_index(msg, 16, target_system); // System which should execute the command
put_uint8_t_by_index(msg, 17, target_component); // Component which should execute the command, 0 for all components
put_uint8_t_by_index(msg, 18, command); // Command ID, as defined by MAV_CMD enum.
put_uint8_t_by_index(msg, 19, confirmation); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT;
return mavlink_finalize_message(msg, system_id, component_id, 20, 160); return mavlink_finalize_message(msg, system_id, component_id, 20, 160);
} }
...@@ -87,17 +103,33 @@ static inline uint16_t mavlink_msg_command_short_pack_chan(uint8_t system_id, ui ...@@ -87,17 +103,33 @@ static inline uint16_t mavlink_msg_command_short_pack_chan(uint8_t system_id, ui
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t command,uint8_t confirmation,float param1,float param2,float param3,float param4) uint8_t target_system,uint8_t target_component,uint8_t command,uint8_t confirmation,float param1,float param2,float param3,float param4)
{ {
msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
_mav_put_uint8_t(buf, 18, command);
_mav_put_uint8_t(buf, 19, confirmation);
put_float_by_index(msg, 0, param1); // Parameter 1, as defined by MAV_CMD enum. memcpy(_MAV_PAYLOAD(msg), buf, 20);
put_float_by_index(msg, 4, param2); // Parameter 2, as defined by MAV_CMD enum. #else
put_float_by_index(msg, 8, param3); // Parameter 3, as defined by MAV_CMD enum. mavlink_command_short_t packet;
put_float_by_index(msg, 12, param4); // Parameter 4, as defined by MAV_CMD enum. packet.param1 = param1;
put_uint8_t_by_index(msg, 16, target_system); // System which should execute the command packet.param2 = param2;
put_uint8_t_by_index(msg, 17, target_component); // Component which should execute the command, 0 for all components packet.param3 = param3;
put_uint8_t_by_index(msg, 18, command); // Command ID, as defined by MAV_CMD enum. packet.param4 = param4;
put_uint8_t_by_index(msg, 19, confirmation); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) packet.target_system = target_system;
packet.target_component = target_component;
packet.command = command;
packet.confirmation = confirmation;
memcpy(_MAV_PAYLOAD(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 160); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 160);
} }
...@@ -131,19 +163,31 @@ static inline uint16_t mavlink_msg_command_short_encode(uint8_t system_id, uint8 ...@@ -131,19 +163,31 @@ static inline uint16_t mavlink_msg_command_short_encode(uint8_t system_id, uint8
static inline void mavlink_msg_command_short_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) static inline void mavlink_msg_command_short_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 20); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT; char buf[20];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
_mav_put_uint8_t(buf, 18, command);
_mav_put_uint8_t(buf, 19, confirmation);
put_float_by_index(msg, 0, param1); // Parameter 1, as defined by MAV_CMD enum. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_SHORT, buf, 20, 160);
put_float_by_index(msg, 4, param2); // Parameter 2, as defined by MAV_CMD enum. #else
put_float_by_index(msg, 8, param3); // Parameter 3, as defined by MAV_CMD enum. mavlink_command_short_t packet;
put_float_by_index(msg, 12, param4); // Parameter 4, as defined by MAV_CMD enum. packet.param1 = param1;
put_uint8_t_by_index(msg, 16, target_system); // System which should execute the command packet.param2 = param2;
put_uint8_t_by_index(msg, 17, target_component); // Component which should execute the command, 0 for all components packet.param3 = param3;
put_uint8_t_by_index(msg, 18, command); // Command ID, as defined by MAV_CMD enum. packet.param4 = param4;
put_uint8_t_by_index(msg, 19, confirmation); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) packet.target_system = target_system;
packet.target_component = target_component;
packet.command = command;
packet.confirmation = confirmation;
mavlink_finalize_message_chan_send(msg, chan, 20, 160); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_SHORT, (const char *)&packet, 20, 160);
#endif
} }
#endif #endif
...@@ -158,7 +202,7 @@ static inline void mavlink_msg_command_short_send(mavlink_channel_t chan, uint8_ ...@@ -158,7 +202,7 @@ static inline void mavlink_msg_command_short_send(mavlink_channel_t chan, uint8_
*/ */
static inline uint8_t mavlink_msg_command_short_get_target_system(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_command_short_get_target_system(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 16); return _MAV_RETURN_uint8_t(msg, 16);
} }
/** /**
...@@ -168,7 +212,7 @@ static inline uint8_t mavlink_msg_command_short_get_target_system(const mavlink_ ...@@ -168,7 +212,7 @@ static inline uint8_t mavlink_msg_command_short_get_target_system(const mavlink_
*/ */
static inline uint8_t mavlink_msg_command_short_get_target_component(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_command_short_get_target_component(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 17); return _MAV_RETURN_uint8_t(msg, 17);
} }
/** /**
...@@ -178,7 +222,7 @@ static inline uint8_t mavlink_msg_command_short_get_target_component(const mavli ...@@ -178,7 +222,7 @@ static inline uint8_t mavlink_msg_command_short_get_target_component(const mavli
*/ */
static inline uint8_t mavlink_msg_command_short_get_command(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_command_short_get_command(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 18); return _MAV_RETURN_uint8_t(msg, 18);
} }
/** /**
...@@ -188,7 +232,7 @@ static inline uint8_t mavlink_msg_command_short_get_command(const mavlink_messag ...@@ -188,7 +232,7 @@ static inline uint8_t mavlink_msg_command_short_get_command(const mavlink_messag
*/ */
static inline uint8_t mavlink_msg_command_short_get_confirmation(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_command_short_get_confirmation(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 19); return _MAV_RETURN_uint8_t(msg, 19);
} }
/** /**
...@@ -198,7 +242,7 @@ static inline uint8_t mavlink_msg_command_short_get_confirmation(const mavlink_m ...@@ -198,7 +242,7 @@ static inline uint8_t mavlink_msg_command_short_get_confirmation(const mavlink_m
*/ */
static inline float mavlink_msg_command_short_get_param1(const mavlink_message_t* msg) static inline float mavlink_msg_command_short_get_param1(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 0); return _MAV_RETURN_float(msg, 0);
} }
/** /**
...@@ -208,7 +252,7 @@ static inline float mavlink_msg_command_short_get_param1(const mavlink_message_t ...@@ -208,7 +252,7 @@ static inline float mavlink_msg_command_short_get_param1(const mavlink_message_t
*/ */
static inline float mavlink_msg_command_short_get_param2(const mavlink_message_t* msg) static inline float mavlink_msg_command_short_get_param2(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 4); return _MAV_RETURN_float(msg, 4);
} }
/** /**
...@@ -218,7 +262,7 @@ static inline float mavlink_msg_command_short_get_param2(const mavlink_message_t ...@@ -218,7 +262,7 @@ static inline float mavlink_msg_command_short_get_param2(const mavlink_message_t
*/ */
static inline float mavlink_msg_command_short_get_param3(const mavlink_message_t* msg) static inline float mavlink_msg_command_short_get_param3(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 8); return _MAV_RETURN_float(msg, 8);
} }
/** /**
...@@ -228,7 +272,7 @@ static inline float mavlink_msg_command_short_get_param3(const mavlink_message_t ...@@ -228,7 +272,7 @@ static inline float mavlink_msg_command_short_get_param3(const mavlink_message_t
*/ */
static inline float mavlink_msg_command_short_get_param4(const mavlink_message_t* msg) static inline float mavlink_msg_command_short_get_param4(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 12); return _MAV_RETURN_float(msg, 12);
} }
/** /**
...@@ -249,6 +293,6 @@ static inline void mavlink_msg_command_short_decode(const mavlink_message_t* msg ...@@ -249,6 +293,6 @@ static inline void mavlink_msg_command_short_decode(const mavlink_message_t* msg
command_short->command = mavlink_msg_command_short_get_command(msg); command_short->command = mavlink_msg_command_short_get_command(msg);
command_short->confirmation = mavlink_msg_command_short_get_confirmation(msg); command_short->confirmation = mavlink_msg_command_short_get_confirmation(msg);
#else #else
memcpy(command_short, MAVLINK_PAYLOAD(msg), 20); memcpy(command_short, _MAV_PAYLOAD(msg), 20);
#endif #endif
} }
...@@ -38,12 +38,23 @@ typedef struct __mavlink_data_stream_t ...@@ -38,12 +38,23 @@ typedef struct __mavlink_data_stream_t
static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t stream_id, uint16_t message_rate, uint8_t on_off) uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
{ {
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
memcpy(_MAV_PAYLOAD(msg), buf, 4);
#else
mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
put_uint16_t_by_index(msg, 0, message_rate); // The requested interval between two messages of this type memcpy(_MAV_PAYLOAD(msg), &packet, 4);
put_uint8_t_by_index(msg, 2, stream_id); // The ID of the requested data stream #endif
put_uint8_t_by_index(msg, 3, on_off); // 1 stream is enabled, 0 stream is stopped.
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
return mavlink_finalize_message(msg, system_id, component_id, 4, 21); return mavlink_finalize_message(msg, system_id, component_id, 4, 21);
} }
...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint ...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t stream_id,uint16_t message_rate,uint8_t on_off) uint8_t stream_id,uint16_t message_rate,uint8_t on_off)
{ {
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
put_uint16_t_by_index(msg, 0, message_rate); // The requested interval between two messages of this type memcpy(_MAV_PAYLOAD(msg), buf, 4);
put_uint8_t_by_index(msg, 2, stream_id); // The ID of the requested data stream #else
put_uint8_t_by_index(msg, 3, on_off); // 1 stream is enabled, 0 stream is stopped. mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21);
} }
...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t ...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t
static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 4); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; char buf[4];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
put_uint16_t_by_index(msg, 0, message_rate); // The requested interval between two messages of this type _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, 4, 21);
put_uint8_t_by_index(msg, 2, stream_id); // The ID of the requested data stream #else
put_uint8_t_by_index(msg, 3, on_off); // 1 stream is enabled, 0 stream is stopped. mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
mavlink_finalize_message_chan_send(msg, chan, 4, 21); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, 4, 21);
#endif
} }
#endif #endif
...@@ -118,7 +147,7 @@ static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t ...@@ -118,7 +147,7 @@ static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t
*/ */
static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 2); return _MAV_RETURN_uint8_t(msg, 2);
} }
/** /**
...@@ -128,7 +157,7 @@ static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_messag ...@@ -128,7 +157,7 @@ static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_messag
*/ */
static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint16_t(msg, 0); return _MAV_RETURN_uint16_t(msg, 0);
} }
/** /**
...@@ -138,7 +167,7 @@ static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_me ...@@ -138,7 +167,7 @@ static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_me
*/ */
static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 3); return _MAV_RETURN_uint8_t(msg, 3);
} }
/** /**
...@@ -154,6 +183,6 @@ static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, ...@@ -154,6 +183,6 @@ static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg,
data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg);
data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg);
#else #else
memcpy(data_stream, MAVLINK_PAYLOAD(msg), 4); memcpy(data_stream, _MAV_PAYLOAD(msg), 4);
#endif #endif
} }
...@@ -38,12 +38,23 @@ typedef struct __mavlink_debug_t ...@@ -38,12 +38,23 @@ typedef struct __mavlink_debug_t
static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t ind, float value) uint32_t time_boot_ms, uint8_t ind, float value)
{ {
msg->msgid = MAVLINK_MSG_ID_DEBUG; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
memcpy(_MAV_PAYLOAD(msg), buf, 9);
#else
mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) memcpy(_MAV_PAYLOAD(msg), &packet, 9);
put_float_by_index(msg, 4, value); // DEBUG value #endif
put_uint8_t_by_index(msg, 8, ind); // index of debug variable
msg->msgid = MAVLINK_MSG_ID_DEBUG;
return mavlink_finalize_message(msg, system_id, component_id, 9, 46); return mavlink_finalize_message(msg, system_id, component_id, 9, 46);
} }
...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co ...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co
mavlink_message_t* msg, mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t ind,float value) uint32_t time_boot_ms,uint8_t ind,float value)
{ {
msg->msgid = MAVLINK_MSG_ID_DEBUG; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) memcpy(_MAV_PAYLOAD(msg), buf, 9);
put_float_by_index(msg, 4, value); // DEBUG value #else
put_uint8_t_by_index(msg, 8, ind); // index of debug variable mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46);
} }
...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo ...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 9); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_DEBUG; char buf[9];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, 9, 46);
put_float_by_index(msg, 4, value); // DEBUG value #else
put_uint8_t_by_index(msg, 8, ind); // index of debug variable mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
mavlink_finalize_message_chan_send(msg, chan, 9, 46); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, 9, 46);
#endif
} }
#endif #endif
...@@ -118,7 +147,7 @@ static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_ ...@@ -118,7 +147,7 @@ static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_
*/ */
static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint32_t(msg, 0); return _MAV_RETURN_uint32_t(msg, 0);
} }
/** /**
...@@ -128,7 +157,7 @@ static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_ ...@@ -128,7 +157,7 @@ static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_
*/ */
static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 8); return _MAV_RETURN_uint8_t(msg, 8);
} }
/** /**
...@@ -138,7 +167,7 @@ static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) ...@@ -138,7 +167,7 @@ static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
*/ */
static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 4); return _MAV_RETURN_float(msg, 4);
} }
/** /**
...@@ -154,6 +183,6 @@ static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlin ...@@ -154,6 +183,6 @@ static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlin
debug->value = mavlink_msg_debug_get_value(msg); debug->value = mavlink_msg_debug_get_value(msg);
debug->ind = mavlink_msg_debug_get_ind(msg); debug->ind = mavlink_msg_debug_get_ind(msg);
#else #else
memcpy(debug, MAVLINK_PAYLOAD(msg), 9); memcpy(debug, _MAV_PAYLOAD(msg), 9);
#endif #endif
} }
...@@ -44,14 +44,25 @@ typedef struct __mavlink_debug_vect_t ...@@ -44,14 +44,25 @@ typedef struct __mavlink_debug_vect_t
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, uint64_t time_usec, float x, float y, float z) const char *name, uint64_t time_usec, float x, float y, float z)
{ {
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp _mav_put_uint64_t(buf, 0, time_usec);
put_float_by_index(msg, 8, x); // x _mav_put_float(buf, 8, x);
put_float_by_index(msg, 12, y); // y _mav_put_float(buf, 12, y);
put_float_by_index(msg, 16, z); // z _mav_put_float(buf, 16, z);
put_char_array_by_index(msg, 20, name, 10); // Name _mav_put_char_array(buf, 20, name, 10);
memcpy(_MAV_PAYLOAD(msg), buf, 30);
#else
mavlink_debug_vect_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD(msg), &packet, 30);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
return mavlink_finalize_message(msg, system_id, component_id, 30, 49); return mavlink_finalize_message(msg, system_id, component_id, 30, 49);
} }
...@@ -72,14 +83,25 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8 ...@@ -72,14 +83,25 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8
mavlink_message_t* msg, mavlink_message_t* msg,
const char *name,uint64_t time_usec,float x,float y,float z) const char *name,uint64_t time_usec,float x,float y,float z)
{ {
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp _mav_put_uint64_t(buf, 0, time_usec);
put_float_by_index(msg, 8, x); // x _mav_put_float(buf, 8, x);
put_float_by_index(msg, 12, y); // y _mav_put_float(buf, 12, y);
put_float_by_index(msg, 16, z); // z _mav_put_float(buf, 16, z);
put_char_array_by_index(msg, 20, name, 10); // Name _mav_put_char_array(buf, 20, name, 10);
memcpy(_MAV_PAYLOAD(msg), buf, 30);
#else
mavlink_debug_vect_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD(msg), &packet, 30);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49);
} }
...@@ -110,16 +132,23 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t ...@@ -110,16 +132,23 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 30); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
put_uint64_t_by_index(msg, 0, time_usec); // Timestamp _mav_put_float(buf, 8, x);
put_float_by_index(msg, 8, x); // x _mav_put_float(buf, 12, y);
put_float_by_index(msg, 12, y); // y _mav_put_float(buf, 16, z);
put_float_by_index(msg, 16, z); // z _mav_put_char_array(buf, 20, name, 10);
put_char_array_by_index(msg, 20, name, 10); // Name _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30, 49);
#else
mavlink_finalize_message_chan_send(msg, chan, 30, 49); mavlink_debug_vect_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30, 49);
#endif
} }
#endif #endif
...@@ -134,7 +163,7 @@ static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const cha ...@@ -134,7 +163,7 @@ static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const cha
*/ */
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
{ {
return MAVLINK_MSG_RETURN_char_array(msg, name, 10, 20); return _MAV_RETURN_char_array(msg, name, 10, 20);
} }
/** /**
...@@ -144,7 +173,7 @@ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* ...@@ -144,7 +173,7 @@ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t*
*/ */
static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint64_t(msg, 0); return _MAV_RETURN_uint64_t(msg, 0);
} }
/** /**
...@@ -154,7 +183,7 @@ static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_messag ...@@ -154,7 +183,7 @@ static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_messag
*/ */
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 8); return _MAV_RETURN_float(msg, 8);
} }
/** /**
...@@ -164,7 +193,7 @@ static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) ...@@ -164,7 +193,7 @@ static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
*/ */
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 12); return _MAV_RETURN_float(msg, 12);
} }
/** /**
...@@ -174,7 +203,7 @@ static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) ...@@ -174,7 +203,7 @@ static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
*/ */
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 16); return _MAV_RETURN_float(msg, 16);
} }
/** /**
...@@ -192,6 +221,6 @@ static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, m ...@@ -192,6 +221,6 @@ static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, m
debug_vect->z = mavlink_msg_debug_vect_get_z(msg); debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
mavlink_msg_debug_vect_get_name(msg, debug_vect->name); mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
#else #else
memcpy(debug_vect, MAVLINK_PAYLOAD(msg), 30); memcpy(debug_vect, _MAV_PAYLOAD(msg), 30);
#endif #endif
} }
...@@ -38,12 +38,23 @@ typedef struct __mavlink_extended_message_t ...@@ -38,12 +38,23 @@ typedef struct __mavlink_extended_message_t
static inline uint16_t mavlink_msg_extended_message_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_extended_message_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t protocol_flags) uint8_t target_system, uint8_t target_component, uint8_t protocol_flags)
{ {
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, protocol_flags);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
#else
mavlink_extended_message_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.protocol_flags = protocol_flags;
put_uint8_t_by_index(msg, 0, target_system); // System which should execute the command memcpy(_MAV_PAYLOAD(msg), &packet, 3);
put_uint8_t_by_index(msg, 1, target_component); // Component which should execute the command, 0 for all components #endif
put_uint8_t_by_index(msg, 2, protocol_flags); // Retransmission / ACK flags
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
return mavlink_finalize_message(msg, system_id, component_id, 3, 247); return mavlink_finalize_message(msg, system_id, component_id, 3, 247);
} }
...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_extended_message_pack_chan(uint8_t system_id, ...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_extended_message_pack_chan(uint8_t system_id,
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t protocol_flags) uint8_t target_system,uint8_t target_component,uint8_t protocol_flags)
{ {
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, protocol_flags);
put_uint8_t_by_index(msg, 0, target_system); // System which should execute the command memcpy(_MAV_PAYLOAD(msg), buf, 3);
put_uint8_t_by_index(msg, 1, target_component); // Component which should execute the command, 0 for all components #else
put_uint8_t_by_index(msg, 2, protocol_flags); // Retransmission / ACK flags mavlink_extended_message_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.protocol_flags = protocol_flags;
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 247); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 247);
} }
...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_extended_message_encode(uint8_t system_id, ui ...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_extended_message_encode(uint8_t system_id, ui
static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t protocol_flags) static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t protocol_flags)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 3); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, protocol_flags);
put_uint8_t_by_index(msg, 0, target_system); // System which should execute the command _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_MESSAGE, buf, 3, 247);
put_uint8_t_by_index(msg, 1, target_component); // Component which should execute the command, 0 for all components #else
put_uint8_t_by_index(msg, 2, protocol_flags); // Retransmission / ACK flags mavlink_extended_message_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.protocol_flags = protocol_flags;
mavlink_finalize_message_chan_send(msg, chan, 3, 247); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_MESSAGE, (const char *)&packet, 3, 247);
#endif
} }
#endif #endif
...@@ -118,7 +147,7 @@ static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uin ...@@ -118,7 +147,7 @@ static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uin
*/ */
static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 0); return _MAV_RETURN_uint8_t(msg, 0);
} }
/** /**
...@@ -128,7 +157,7 @@ static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavli ...@@ -128,7 +157,7 @@ static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavli
*/ */
static inline uint8_t mavlink_msg_extended_message_get_target_component(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_extended_message_get_target_component(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 1); return _MAV_RETURN_uint8_t(msg, 1);
} }
/** /**
...@@ -138,7 +167,7 @@ static inline uint8_t mavlink_msg_extended_message_get_target_component(const ma ...@@ -138,7 +167,7 @@ static inline uint8_t mavlink_msg_extended_message_get_target_component(const ma
*/ */
static inline uint8_t mavlink_msg_extended_message_get_protocol_flags(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_extended_message_get_protocol_flags(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 2); return _MAV_RETURN_uint8_t(msg, 2);
} }
/** /**
...@@ -154,6 +183,6 @@ static inline void mavlink_msg_extended_message_decode(const mavlink_message_t* ...@@ -154,6 +183,6 @@ static inline void mavlink_msg_extended_message_decode(const mavlink_message_t*
extended_message->target_component = mavlink_msg_extended_message_get_target_component(msg); extended_message->target_component = mavlink_msg_extended_message_get_target_component(msg);
extended_message->protocol_flags = mavlink_msg_extended_message_get_protocol_flags(msg); extended_message->protocol_flags = mavlink_msg_extended_message_get_protocol_flags(msg);
#else #else
memcpy(extended_message, MAVLINK_PAYLOAD(msg), 3); memcpy(extended_message, _MAV_PAYLOAD(msg), 3);
#endif #endif
} }
// MESSAGE GLOBAL_POSITION PACKING
#define MAVLINK_MSG_ID_GLOBAL_POSITION 33
typedef struct __mavlink_global_position_t
{
uint64_t usec; ///< Timestamp (microseconds since unix epoch)
float lat; ///< Latitude, in degrees
float lon; ///< Longitude, in degrees
float alt; ///< Absolute altitude, in meters
float vx; ///< X Speed (in Latitude direction, positive: going north)
float vy; ///< Y Speed (in Longitude direction, positive: going east)
float vz; ///< Z Speed (in Altitude direction, positive: going up)
} mavlink_global_position_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_LEN 32
#define MAVLINK_MSG_ID_33_LEN 32
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \
"GLOBAL_POSITION", \
7, \
{ { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \
{ "lat", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \
{ "lon", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \
{ "alt", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \
{ "vx", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \
{ "vy", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \
{ "vz", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \
} \
}
/**
* @brief Pack a global_position 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 (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
return mavlink_finalize_message(msg, system_id, component_id, 32, 147);
}
/**
* @brief Pack a global_position message on a channel
* @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 (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float lat,float lon,float alt,float vx,float vy,float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 147);
}
/**
* @brief Encode a global_position 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 global_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
{
return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
}
/**
* @brief Send a global_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, buf, 32, 147);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, (const char *)&packet, 32, 147);
#endif
}
#endif
// MESSAGE GLOBAL_POSITION UNPACKING
/**
* @brief Get field usec from global_position message
*
* @return Timestamp (microseconds since unix epoch)
*/
static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field lat from global_position message
*
* @return Latitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field lon from global_position message
*
* @return Longitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field alt from global_position message
*
* @return Absolute altitude, in meters
*/
static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field vx from global_position message
*
* @return X Speed (in Latitude direction, positive: going north)
*/
static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field vy from global_position message
*
* @return Y Speed (in Longitude direction, positive: going east)
*/
static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field vz from global_position message
*
* @return Z Speed (in Altitude direction, positive: going up)
*/
static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a global_position message into a struct
*
* @param msg The message to decode
* @param global_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position->usec = mavlink_msg_global_position_get_usec(msg);
global_position->lat = mavlink_msg_global_position_get_lat(msg);
global_position->lon = mavlink_msg_global_position_get_lon(msg);
global_position->alt = mavlink_msg_global_position_get_alt(msg);
global_position->vx = mavlink_msg_global_position_get_vx(msg);
global_position->vy = mavlink_msg_global_position_get_vy(msg);
global_position->vz = mavlink_msg_global_position_get_vz(msg);
#else
memcpy(global_position, _MAV_PAYLOAD(msg), 32);
#endif
}
...@@ -53,17 +53,33 @@ typedef struct __mavlink_global_position_int_t ...@@ -53,17 +53,33 @@ typedef struct __mavlink_global_position_int_t
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{ {
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, alt);
_mav_put_int16_t(buf, 16, vx);
_mav_put_int16_t(buf, 18, vy);
_mav_put_int16_t(buf, 20, vz);
_mav_put_uint16_t(buf, 22, hdg);
memcpy(_MAV_PAYLOAD(msg), buf, 24);
#else
mavlink_global_position_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.hdg = hdg;
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) memcpy(_MAV_PAYLOAD(msg), &packet, 24);
put_int32_t_by_index(msg, 4, lat); // Latitude, expressed as * 1E7 #endif
put_int32_t_by_index(msg, 8, lon); // Longitude, expressed as * 1E7
put_int32_t_by_index(msg, 12, alt); // Altitude in meters, expressed as * 1000 (millimeters), above MSL
put_int16_t_by_index(msg, 16, vx); // Ground X Speed (Latitude), expressed as m/s * 100
put_int16_t_by_index(msg, 18, vy); // Ground Y Speed (Longitude), expressed as m/s * 100
put_int16_t_by_index(msg, 20, vz); // Ground Z Speed (Altitude), expressed as m/s * 100
put_uint16_t_by_index(msg, 22, hdg); // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
return mavlink_finalize_message(msg, system_id, component_id, 24, 102); return mavlink_finalize_message(msg, system_id, component_id, 24, 102);
} }
...@@ -87,17 +103,33 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_ ...@@ -87,17 +103,33 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
mavlink_message_t* msg, mavlink_message_t* msg,
uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
{ {
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, alt);
_mav_put_int16_t(buf, 16, vx);
_mav_put_int16_t(buf, 18, vy);
_mav_put_int16_t(buf, 20, vz);
_mav_put_uint16_t(buf, 22, hdg);
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) memcpy(_MAV_PAYLOAD(msg), buf, 24);
put_int32_t_by_index(msg, 4, lat); // Latitude, expressed as * 1E7 #else
put_int32_t_by_index(msg, 8, lon); // Longitude, expressed as * 1E7 mavlink_global_position_int_t packet;
put_int32_t_by_index(msg, 12, alt); // Altitude in meters, expressed as * 1000 (millimeters), above MSL packet.time_boot_ms = time_boot_ms;
put_int16_t_by_index(msg, 16, vx); // Ground X Speed (Latitude), expressed as m/s * 100 packet.lat = lat;
put_int16_t_by_index(msg, 18, vy); // Ground Y Speed (Longitude), expressed as m/s * 100 packet.lon = lon;
put_int16_t_by_index(msg, 20, vz); // Ground Z Speed (Altitude), expressed as m/s * 100 packet.alt = alt;
put_uint16_t_by_index(msg, 22, hdg); // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.hdg = hdg;
memcpy(_MAV_PAYLOAD(msg), &packet, 24);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 102); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 102);
} }
...@@ -131,19 +163,31 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, ...@@ -131,19 +163,31 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id,
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 24); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; char buf[24];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, alt);
_mav_put_int16_t(buf, 16, vx);
_mav_put_int16_t(buf, 18, vy);
_mav_put_int16_t(buf, 20, vz);
_mav_put_uint16_t(buf, 22, hdg);
put_uint32_t_by_index(msg, 0, time_boot_ms); // Timestamp (milliseconds since system boot) _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 24, 102);
put_int32_t_by_index(msg, 4, lat); // Latitude, expressed as * 1E7 #else
put_int32_t_by_index(msg, 8, lon); // Longitude, expressed as * 1E7 mavlink_global_position_int_t packet;
put_int32_t_by_index(msg, 12, alt); // Altitude in meters, expressed as * 1000 (millimeters), above MSL packet.time_boot_ms = time_boot_ms;
put_int16_t_by_index(msg, 16, vx); // Ground X Speed (Latitude), expressed as m/s * 100 packet.lat = lat;
put_int16_t_by_index(msg, 18, vy); // Ground Y Speed (Longitude), expressed as m/s * 100 packet.lon = lon;
put_int16_t_by_index(msg, 20, vz); // Ground Z Speed (Altitude), expressed as m/s * 100 packet.alt = alt;
put_uint16_t_by_index(msg, 22, hdg); // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.hdg = hdg;
mavlink_finalize_message_chan_send(msg, chan, 24, 102); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 24, 102);
#endif
} }
#endif #endif
...@@ -158,7 +202,7 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, ...@@ -158,7 +202,7 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan,
*/ */
static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint32_t(msg, 0); return _MAV_RETURN_uint32_t(msg, 0);
} }
/** /**
...@@ -168,7 +212,7 @@ static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const ma ...@@ -168,7 +212,7 @@ static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const ma
*/ */
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 4); return _MAV_RETURN_int32_t(msg, 4);
} }
/** /**
...@@ -178,7 +222,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_mess ...@@ -178,7 +222,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_mess
*/ */
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 8); return _MAV_RETURN_int32_t(msg, 8);
} }
/** /**
...@@ -188,7 +232,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess ...@@ -188,7 +232,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
*/ */
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 12); return _MAV_RETURN_int32_t(msg, 12);
} }
/** /**
...@@ -198,7 +242,7 @@ static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_mess ...@@ -198,7 +242,7 @@ static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_mess
*/ */
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 16); return _MAV_RETURN_int16_t(msg, 16);
} }
/** /**
...@@ -208,7 +252,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_messa ...@@ -208,7 +252,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_messa
*/ */
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 18); return _MAV_RETURN_int16_t(msg, 18);
} }
/** /**
...@@ -218,7 +262,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_messa ...@@ -218,7 +262,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_messa
*/ */
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 20); return _MAV_RETURN_int16_t(msg, 20);
} }
/** /**
...@@ -228,7 +272,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa ...@@ -228,7 +272,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa
*/ */
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint16_t(msg, 22); return _MAV_RETURN_uint16_t(msg, 22);
} }
/** /**
...@@ -249,6 +293,6 @@ static inline void mavlink_msg_global_position_int_decode(const mavlink_message_ ...@@ -249,6 +293,6 @@ static inline void mavlink_msg_global_position_int_decode(const mavlink_message_
global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
#else #else
memcpy(global_position_int, MAVLINK_PAYLOAD(msg), 24); memcpy(global_position_int, _MAV_PAYLOAD(msg), 24);
#endif #endif
} }
...@@ -41,13 +41,25 @@ typedef struct __mavlink_global_position_setpoint_int_t ...@@ -41,13 +41,25 @@ typedef struct __mavlink_global_position_setpoint_int_t
static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{ {
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
put_int32_t_by_index(msg, 0, latitude); // WGS84 Latitude position in degrees * 1E7 memcpy(_MAV_PAYLOAD(msg), &packet, 14);
put_int32_t_by_index(msg, 4, longitude); // WGS84 Longitude position in degrees * 1E7 #endif
put_int32_t_by_index(msg, 8, altitude); // WGS84 Altitude in meters * 1000 (positive for up)
put_int16_t_by_index(msg, 12, yaw); // Desired yaw angle in degrees * 100
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message(msg, system_id, component_id, 14, 142); return mavlink_finalize_message(msg, system_id, component_id, 14, 142);
} }
...@@ -67,13 +79,25 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_ ...@@ -67,13 +79,25 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_
mavlink_message_t* msg, mavlink_message_t* msg,
int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw)
{ {
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
put_int32_t_by_index(msg, 0, latitude); // WGS84 Latitude position in degrees * 1E7 memcpy(_MAV_PAYLOAD(msg), &packet, 14);
put_int32_t_by_index(msg, 4, longitude); // WGS84 Longitude position in degrees * 1E7 #endif
put_int32_t_by_index(msg, 8, altitude); // WGS84 Altitude in meters * 1000 (positive for up)
put_int16_t_by_index(msg, 12, yaw); // Desired yaw angle in degrees * 100
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 142); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 142);
} }
...@@ -103,15 +127,23 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t s ...@@ -103,15 +127,23 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t s
static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 14); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; char buf[14];
_mav_put_int32_t(buf, 0, latitude);
put_int32_t_by_index(msg, 0, latitude); // WGS84 Latitude position in degrees * 1E7 _mav_put_int32_t(buf, 4, longitude);
put_int32_t_by_index(msg, 4, longitude); // WGS84 Longitude position in degrees * 1E7 _mav_put_int32_t(buf, 8, altitude);
put_int32_t_by_index(msg, 8, altitude); // WGS84 Altitude in meters * 1000 (positive for up) _mav_put_int16_t(buf, 12, yaw);
put_int16_t_by_index(msg, 12, yaw); // Desired yaw angle in degrees * 100
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 14, 142);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
mavlink_finalize_message_chan_send(msg, chan, 14, 142); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 14, 142);
#endif
} }
#endif #endif
...@@ -126,7 +158,7 @@ static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel ...@@ -126,7 +158,7 @@ static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel
*/ */
static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 0); return _MAV_RETURN_int32_t(msg, 0);
} }
/** /**
...@@ -136,7 +168,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(cons ...@@ -136,7 +168,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(cons
*/ */
static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 4); return _MAV_RETURN_int32_t(msg, 4);
} }
/** /**
...@@ -146,7 +178,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(con ...@@ -146,7 +178,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(con
*/ */
static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 8); return _MAV_RETURN_int32_t(msg, 8);
} }
/** /**
...@@ -156,7 +188,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(cons ...@@ -156,7 +188,7 @@ static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(cons
*/ */
static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int16_t(msg, 12); return _MAV_RETURN_int16_t(msg, 12);
} }
/** /**
...@@ -173,6 +205,6 @@ static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink ...@@ -173,6 +205,6 @@ static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink
global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg); global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg);
global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg); global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg);
#else #else
memcpy(global_position_setpoint_int, MAVLINK_PAYLOAD(msg), 14); memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 14);
#endif #endif
} }
...@@ -38,12 +38,23 @@ typedef struct __mavlink_gps_global_origin_t ...@@ -38,12 +38,23 @@ typedef struct __mavlink_gps_global_origin_t
static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude) int32_t latitude, int32_t longitude, int32_t altitude)
{ {
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
put_int32_t_by_index(msg, 0, latitude); // Latitude (WGS84), expressed as * 1E7 memcpy(_MAV_PAYLOAD(msg), &packet, 12);
put_int32_t_by_index(msg, 4, longitude); // Longitude (WGS84), expressed as * 1E7 #endif
put_int32_t_by_index(msg, 8, altitude); // Altitude(WGS84), expressed as * 1000
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
return mavlink_finalize_message(msg, system_id, component_id, 12, 39); return mavlink_finalize_message(msg, system_id, component_id, 12, 39);
} }
...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id ...@@ -62,12 +73,23 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id
mavlink_message_t* msg, mavlink_message_t* msg,
int32_t latitude,int32_t longitude,int32_t altitude) int32_t latitude,int32_t longitude,int32_t altitude)
{ {
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
put_int32_t_by_index(msg, 0, latitude); // Latitude (WGS84), expressed as * 1E7 memcpy(_MAV_PAYLOAD(msg), buf, 12);
put_int32_t_by_index(msg, 4, longitude); // Longitude (WGS84), expressed as * 1E7 #else
put_int32_t_by_index(msg, 8, altitude); // Altitude(WGS84), expressed as * 1000 mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39);
} }
...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, u ...@@ -96,14 +118,21 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, u
static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 12); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
put_int32_t_by_index(msg, 0, latitude); // Latitude (WGS84), expressed as * 1E7 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, 12, 39);
put_int32_t_by_index(msg, 4, longitude); // Longitude (WGS84), expressed as * 1E7 #else
put_int32_t_by_index(msg, 8, altitude); // Altitude(WGS84), expressed as * 1000 mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
mavlink_finalize_message_chan_send(msg, chan, 12, 39); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, 12, 39);
#endif
} }
#endif #endif
...@@ -118,7 +147,7 @@ static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, in ...@@ -118,7 +147,7 @@ static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, in
*/ */
static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 0); return _MAV_RETURN_int32_t(msg, 0);
} }
/** /**
...@@ -128,7 +157,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_m ...@@ -128,7 +157,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_m
*/ */
static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 4); return _MAV_RETURN_int32_t(msg, 4);
} }
/** /**
...@@ -138,7 +167,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_ ...@@ -138,7 +167,7 @@ static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_
*/ */
static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_int32_t(msg, 8); return _MAV_RETURN_int32_t(msg, 8);
} }
/** /**
...@@ -154,6 +183,6 @@ static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* ...@@ -154,6 +183,6 @@ static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t*
gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg);
gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg);
#else #else
memcpy(gps_global_origin, MAVLINK_PAYLOAD(msg), 12); memcpy(gps_global_origin, _MAV_PAYLOAD(msg), 12);
#endif #endif
} }
This diff is collapsed.
// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48
typedef struct __mavlink_gps_set_global_origin_t
{
int32_t latitude; ///< global position * 1E7
int32_t longitude; ///< global position * 1E7
int32_t altitude; ///< global position * 1000
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_gps_set_global_origin_t;
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN 14
#define MAVLINK_MSG_ID_48_LEN 14
#define MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN { \
"GPS_SET_GLOBAL_ORIGIN", \
5, \
{ { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_set_global_origin_t, latitude) }, \
{ "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_set_global_origin_t, longitude) }, \
{ "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_set_global_origin_t, altitude) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gps_set_global_origin_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gps_set_global_origin_t, target_component) }, \
} \
}
/**
* @brief Pack a gps_set_global_origin 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_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
return mavlink_finalize_message(msg, system_id, component_id, 14, 170);
}
/**
* @brief Pack a gps_set_global_origin message on a channel
* @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_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,int32_t latitude,int32_t longitude,int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 170);
}
/**
* @brief Encode a gps_set_global_origin 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 gps_set_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude);
}
/**
* @brief Send a gps_set_global_origin message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, buf, 14, 170);
#else
mavlink_gps_set_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, (const char *)&packet, 14, 170);
#endif
}
#endif
// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING
/**
* @brief Get field target_system from gps_set_global_origin message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field target_component from gps_set_global_origin message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field latitude from gps_set_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field longitude from gps_set_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field altitude from gps_set_global_origin message
*
* @return global position * 1000
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Decode a gps_set_global_origin message into a struct
*
* @param msg The message to decode
* @param gps_set_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg);
gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg);
gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg);
gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg);
gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg);
#else
memcpy(gps_set_global_origin, _MAV_PAYLOAD(msg), 14);
#endif
}
...@@ -51,15 +51,27 @@ typedef struct __mavlink_gps_status_t ...@@ -51,15 +51,27 @@ typedef struct __mavlink_gps_status_t
static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
{ {
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
put_uint8_t_by_index(msg, 0, satellites_visible); // Number of satellites visible _mav_put_uint8_t(buf, 0, satellites_visible);
put_uint8_t_array_by_index(msg, 1, satellite_prn, 20); // Global satellite ID _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
put_uint8_t_array_by_index(msg, 21, satellite_used, 20); // 0: Satellite not used, 1: used for localization _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
put_uint8_t_array_by_index(msg, 41, satellite_elevation, 20); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
put_uint8_t_array_by_index(msg, 61, satellite_azimuth, 20); // Direction of satellite, 0: 0 deg, 255: 360 deg. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
put_uint8_t_array_by_index(msg, 81, satellite_snr, 20); // Signal to noise ratio of satellite _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
memcpy(_MAV_PAYLOAD(msg), buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD(msg), &packet, 101);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 101, 23); return mavlink_finalize_message(msg, system_id, component_id, 101, 23);
} }
...@@ -81,15 +93,27 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8 ...@@ -81,15 +93,27 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr)
{ {
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
put_uint8_t_by_index(msg, 0, satellites_visible); // Number of satellites visible _mav_put_uint8_t(buf, 0, satellites_visible);
put_uint8_t_array_by_index(msg, 1, satellite_prn, 20); // Global satellite ID _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
put_uint8_t_array_by_index(msg, 21, satellite_used, 20); // 0: Satellite not used, 1: used for localization _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
put_uint8_t_array_by_index(msg, 41, satellite_elevation, 20); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
put_uint8_t_array_by_index(msg, 61, satellite_azimuth, 20); // Direction of satellite, 0: 0 deg, 255: 360 deg. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
put_uint8_t_array_by_index(msg, 81, satellite_snr, 20); // Signal to noise ratio of satellite _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
memcpy(_MAV_PAYLOAD(msg), buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD(msg), &packet, 101);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23);
} }
...@@ -121,17 +145,25 @@ static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t ...@@ -121,17 +145,25 @@ static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t
static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 101); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
put_uint8_t_by_index(msg, 0, satellites_visible); // Number of satellites visible _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
put_uint8_t_array_by_index(msg, 1, satellite_prn, 20); // Global satellite ID _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
put_uint8_t_array_by_index(msg, 21, satellite_used, 20); // 0: Satellite not used, 1: used for localization _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
put_uint8_t_array_by_index(msg, 41, satellite_elevation, 20); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
put_uint8_t_array_by_index(msg, 61, satellite_azimuth, 20); // Direction of satellite, 0: 0 deg, 255: 360 deg. _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
put_uint8_t_array_by_index(msg, 81, satellite_snr, 20); // Signal to noise ratio of satellite _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23);
#else
mavlink_finalize_message_chan_send(msg, chan, 101, 23); mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23);
#endif
} }
#endif #endif
...@@ -146,7 +178,7 @@ static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t s ...@@ -146,7 +178,7 @@ static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t s
*/ */
static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 0); return _MAV_RETURN_uint8_t(msg, 0);
} }
/** /**
...@@ -156,7 +188,7 @@ static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlin ...@@ -156,7 +188,7 @@ static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlin
*/ */
static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
{ {
return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1);
} }
/** /**
...@@ -166,7 +198,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_me ...@@ -166,7 +198,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_me
*/ */
static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
{ {
return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_used, 20, 21); return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21);
} }
/** /**
...@@ -176,7 +208,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_m ...@@ -176,7 +208,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_m
*/ */
static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
{ {
return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41);
} }
/** /**
...@@ -186,7 +218,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavl ...@@ -186,7 +218,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavl
*/ */
static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
{ {
return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61);
} }
/** /**
...@@ -196,7 +228,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlin ...@@ -196,7 +228,7 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlin
*/ */
static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
{ {
return MAVLINK_MSG_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81);
} }
/** /**
...@@ -215,6 +247,6 @@ static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, m ...@@ -215,6 +247,6 @@ static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, m
mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
#else #else
memcpy(gps_status, MAVLINK_PAYLOAD(msg), 101); memcpy(gps_status, _MAV_PAYLOAD(msg), 101);
#endif #endif
} }
...@@ -46,15 +46,29 @@ typedef struct __mavlink_heartbeat_t ...@@ -46,15 +46,29 @@ typedef struct __mavlink_heartbeat_t
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 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, uint8_t base_mode, uint16_t custom_mode, uint8_t system_status) uint8_t type, uint8_t autopilot, uint8_t base_mode, uint16_t custom_mode, uint8_t system_status)
{ {
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[7];
put_uint16_t_by_index(msg, 0, custom_mode); // Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. _mav_put_uint16_t(buf, 0, custom_mode);
put_uint8_t_by_index(msg, 2, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) _mav_put_uint8_t(buf, 2, type);
put_uint8_t_by_index(msg, 3, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM _mav_put_uint8_t(buf, 3, autopilot);
put_uint8_t_by_index(msg, 4, base_mode); // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h _mav_put_uint8_t(buf, 4, base_mode);
put_uint8_t_by_index(msg, 5, system_status); // System status flag, see MAV_STATUS ENUM _mav_put_uint8_t(buf, 5, system_status);
put_uint8_t_by_index(msg, 6, 3); // MAVLink version _mav_put_uint8_t(buf, 6, 3);
memcpy(_MAV_PAYLOAD(msg), buf, 7);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
memcpy(_MAV_PAYLOAD(msg), &packet, 7);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, 7, 88); return mavlink_finalize_message(msg, system_id, component_id, 7, 88);
} }
...@@ -75,15 +89,29 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_ ...@@ -75,15 +89,29 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t type,uint8_t autopilot,uint8_t base_mode,uint16_t custom_mode,uint8_t system_status) uint8_t type,uint8_t autopilot,uint8_t base_mode,uint16_t custom_mode,uint8_t system_status)
{ {
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[7];
put_uint16_t_by_index(msg, 0, custom_mode); // Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. _mav_put_uint16_t(buf, 0, custom_mode);
put_uint8_t_by_index(msg, 2, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) _mav_put_uint8_t(buf, 2, type);
put_uint8_t_by_index(msg, 3, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM _mav_put_uint8_t(buf, 3, autopilot);
put_uint8_t_by_index(msg, 4, base_mode); // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h _mav_put_uint8_t(buf, 4, base_mode);
put_uint8_t_by_index(msg, 5, system_status); // System status flag, see MAV_STATUS ENUM _mav_put_uint8_t(buf, 5, system_status);
put_uint8_t_by_index(msg, 6, 3); // MAVLink version _mav_put_uint8_t(buf, 6, 3);
memcpy(_MAV_PAYLOAD(msg), buf, 7);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
memcpy(_MAV_PAYLOAD(msg), &packet, 7);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 88); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 88);
} }
...@@ -114,17 +142,27 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c ...@@ -114,17 +142,27 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint16_t custom_mode, uint8_t system_status) static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint16_t custom_mode, uint8_t system_status)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 7); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; char buf[7];
_mav_put_uint16_t(buf, 0, custom_mode);
put_uint16_t_by_index(msg, 0, custom_mode); // Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. _mav_put_uint8_t(buf, 2, type);
put_uint8_t_by_index(msg, 2, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) _mav_put_uint8_t(buf, 3, autopilot);
put_uint8_t_by_index(msg, 3, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM _mav_put_uint8_t(buf, 4, base_mode);
put_uint8_t_by_index(msg, 4, base_mode); // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h _mav_put_uint8_t(buf, 5, system_status);
put_uint8_t_by_index(msg, 5, system_status); // System status flag, see MAV_STATUS ENUM _mav_put_uint8_t(buf, 6, 3);
put_uint8_t_by_index(msg, 6, 3); // MAVLink version
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 7, 88);
mavlink_finalize_message_chan_send(msg, chan, 7, 88); #else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 7, 88);
#endif
} }
#endif #endif
...@@ -139,7 +177,7 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty ...@@ -139,7 +177,7 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty
*/ */
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 2); return _MAV_RETURN_uint8_t(msg, 2);
} }
/** /**
...@@ -149,7 +187,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms ...@@ -149,7 +187,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms
*/ */
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 3); return _MAV_RETURN_uint8_t(msg, 3);
} }
/** /**
...@@ -159,7 +197,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_ ...@@ -159,7 +197,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_
*/ */
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 4); return _MAV_RETURN_uint8_t(msg, 4);
} }
/** /**
...@@ -169,7 +207,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_ ...@@ -169,7 +207,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_
*/ */
static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint16_t(msg, 0); return _MAV_RETURN_uint16_t(msg, 0);
} }
/** /**
...@@ -179,7 +217,7 @@ static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa ...@@ -179,7 +217,7 @@ static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa
*/ */
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 5); return _MAV_RETURN_uint8_t(msg, 5);
} }
/** /**
...@@ -189,7 +227,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_mess ...@@ -189,7 +227,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_mess
*/ */
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_uint8_t(msg, 6); return _MAV_RETURN_uint8_t(msg, 6);
} }
/** /**
...@@ -208,6 +246,6 @@ static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, ma ...@@ -208,6 +246,6 @@ static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, ma
heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else #else
memcpy(heartbeat, MAVLINK_PAYLOAD(msg), 7); memcpy(heartbeat, _MAV_PAYLOAD(msg), 7);
#endif #endif
} }
...@@ -41,13 +41,25 @@ typedef struct __mavlink_local_position_setpoint_t ...@@ -41,13 +41,25 @@ typedef struct __mavlink_local_position_setpoint_t
static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float x, float y, float z, float yaw) float x, float y, float z, float yaw)
{ {
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 16);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
put_float_by_index(msg, 0, x); // x position memcpy(_MAV_PAYLOAD(msg), &packet, 16);
put_float_by_index(msg, 4, y); // y position #endif
put_float_by_index(msg, 8, z); // z position
put_float_by_index(msg, 12, yaw); // Desired yaw angle
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 16, 50); return mavlink_finalize_message(msg, system_id, component_id, 16, 50);
} }
...@@ -67,13 +79,25 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys ...@@ -67,13 +79,25 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys
mavlink_message_t* msg, mavlink_message_t* msg,
float x,float y,float z,float yaw) float x,float y,float z,float yaw)
{ {
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 16);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
put_float_by_index(msg, 0, x); // x position memcpy(_MAV_PAYLOAD(msg), &packet, 16);
put_float_by_index(msg, 4, y); // y position #endif
put_float_by_index(msg, 8, z); // z position
put_float_by_index(msg, 12, yaw); // Desired yaw angle
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 50); return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 50);
} }
...@@ -103,15 +127,23 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system ...@@ -103,15 +127,23 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw) static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
{ {
MAVLINK_ALIGNED_MESSAGE(msg, 16); #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; char buf[16];
_mav_put_float(buf, 0, x);
put_float_by_index(msg, 0, x); // x position _mav_put_float(buf, 4, y);
put_float_by_index(msg, 4, y); // y position _mav_put_float(buf, 8, z);
put_float_by_index(msg, 8, z); // z position _mav_put_float(buf, 12, yaw);
put_float_by_index(msg, 12, yaw); // Desired yaw angle
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 16, 50);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
mavlink_finalize_message_chan_send(msg, chan, 16, 50); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 16, 50);
#endif
} }
#endif #endif
...@@ -126,7 +158,7 @@ static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t ch ...@@ -126,7 +158,7 @@ static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t ch
*/ */
static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg) static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 0); return _MAV_RETURN_float(msg, 0);
} }
/** /**
...@@ -136,7 +168,7 @@ static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_mess ...@@ -136,7 +168,7 @@ static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_mess
*/ */
static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg) static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 4); return _MAV_RETURN_float(msg, 4);
} }
/** /**
...@@ -146,7 +178,7 @@ static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_mess ...@@ -146,7 +178,7 @@ static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_mess
*/ */
static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg) static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 8); return _MAV_RETURN_float(msg, 8);
} }
/** /**
...@@ -156,7 +188,7 @@ static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_mess ...@@ -156,7 +188,7 @@ static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_mess
*/ */
static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg) static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
{ {
return MAVLINK_MSG_RETURN_float(msg, 12); return _MAV_RETURN_float(msg, 12);
} }
/** /**
...@@ -173,6 +205,6 @@ static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_mess ...@@ -173,6 +205,6 @@ static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_mess
local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg); local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg);
local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg);
#else #else
memcpy(local_position_setpoint, MAVLINK_PAYLOAD(msg), 16); memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 16);
#endif #endif
} }
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Mon Aug 29 12:10:51 2011" #define MAVLINK_BUILD_DATE "Wed Aug 31 10:19:04 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h" #include "mavlink.h"
......
This diff is collapsed.
...@@ -20,7 +20,11 @@ extern "C" { ...@@ -20,7 +20,11 @@ extern "C" {
#endif #endif
#ifndef MAVLINK_MESSAGE_INFO #ifndef MAVLINK_MESSAGE_INFO
<<<<<<< HEAD
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}} #define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}, {"EMPTY",0,{}}}
=======
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}}
>>>>>>> 720cd74fe31475906a3a527f70f564b1ebc17eb5
#endif #endif
#include "../protocol.h" #include "../protocol.h"
......
...@@ -5,7 +5,11 @@ ...@@ -5,7 +5,11 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
<<<<<<< HEAD
#define MAVLINK_BUILD_DATE "Mon Aug 29 11:49:47 2011" #define MAVLINK_BUILD_DATE "Mon Aug 29 11:49:47 2011"
=======
#define MAVLINK_BUILD_DATE "Wed Aug 31 18:15:07 2011"
>>>>>>> 720cd74fe31475906a3a527f70f564b1ebc17eb5
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h" #include "mavlink.h"
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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