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")
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 += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
......@@ -295,7 +295,7 @@ linux-g++-64 {
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 += && mkdir -p $$DESTDIR/images
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)
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
if (j != 5) {
// 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
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -786,7 +786,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value);
// 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
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -807,7 +807,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key);
// 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
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -819,7 +819,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key);
// 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
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......
......@@ -350,8 +350,8 @@ fgScenery = "--fg-scenery=/Applications/FlightGear.app/Contents/Resources/data/S
#endif
#ifdef Q_OS_WIN32
processFgfs = "C:\Program Files (x86)\FlightGear\bin\Win32\fgfs";
fgRoot = "--fg-root=C:\Program Files (x86)\FlightGear\data";
processFgfs = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs";
fgRoot = "--fg-root=C:\\Program Files (x86)\\FlightGear\\data";
#endif
#ifdef Q_OS_LINUX
......@@ -361,10 +361,9 @@ fgRoot = "--fg-root=/usr/share/flightgear/data";
processCall << fgRoot;
processCall << fgScenery;
processCall << "--generic=socket,out,50,127.0.0.1,49005,udp,ardupilot";
processCall << "--generic=socket,in,50,127.0.0.1,49000,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,qgroundcontrol";
processCall << "--in-air";
processCall << "--altitude=10";
processCall << "--vc=90";
processCall << "--heading=300";
processCall << "--timeofday=noon";
......@@ -386,8 +385,9 @@ if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
processCall << "--prop:/engines/engine[2]/running=true";
processCall << "--prop:/engines/engine[3]/running=true";
}
processCall << QString("--lat=%1").arg(mav->getLatitude());
processCall << QString("--lon=%1").arg(mav->getLongitude());
processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
// Add new argument with this: processCall << "";
processCall << QString("--aircraft=%2").arg(aircraft);
......
......@@ -658,6 +658,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
int component = message.compid;
mavlink_param_union_t val;
val.param_float = value.param_value;
val.type = value.param_type;
// Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP
......@@ -680,22 +681,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
switch (value.param_type)
{
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 parameterChanged(uasId, message.compid, parameterName, val.param_float);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float);
emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param;
}
break;
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 parameterChanged(uasId, message.compid, parameterName, val.param_uint32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32);
emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param;
}
break;
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 parameterChanged(uasId, message.compid, parameterName, val.param_int32);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32);
emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param;
}
break;
default:
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
p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component;
qDebug() << "SENT PARAM:" << value;
// Copy string into buffer, ensuring not to exceed the buffer size
for (unsigned int i = 0; i < sizeof(p.param_id); i++)
{
......
This diff is collapsed.
......@@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text)
if (text.compare("Global") == 0) {
frame = MAV_FRAME_GLOBAL;
} else if (text.compare("Local") == 0) {
frame = MAV_FRAME_LOCAL;
frame = MAV_FRAME_LOCAL_NED;
}
getPosition(lastRobotX, lastRobotY, lastRobotZ);
......@@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void)
getGlobalCursorPosition(getMouseX(), getMouseY(), altitude);
target.set(cursorWorldCoords.first, cursorWorldCoords.second);
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords =
......@@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void)
latitude, longitude);
wp = new Waypoint(0, longitude, latitude, altitude);
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords =
......@@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void)
waypoint->setX(longitude);
waypoint->setY(latitude);
waypoint->setZ(altitude);
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords =
......@@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
Waypoint* waypoint = waypoints.at(selectedWpIndex);
double altitude = waypoint->getZ();
if (frame == MAV_FRAME_LOCAL) {
if (frame == MAV_FRAME_LOCAL_NED) {
altitude = -altitude;
}
......@@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
if (ok) {
if (frame == MAV_FRAME_GLOBAL) {
waypoint->setZ(newAltitude);
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
waypoint->setZ(-newAltitude);
}
}
......@@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z,
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude;
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
x = uas->getLocalX();
y = uas->getLocalY();
z = uas->getLocalZ();
......@@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z,
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude;
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
x = uas->getLocalX();
y = uas->getLocalY();
z = uas->getLocalZ();
......@@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ,
oss.precision(6);
oss << " Cursor [" << cursorLatitude <<
" " << cursorLongitude << "]";
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
oss << " x = " << robotX <<
" y = " << robotY <<
" z = " << robotZ <<
......
......@@ -461,7 +461,7 @@ QVariant QGCGoogleEarthView::documentElement(QString name)
name.prepend("JScript_");
HRESULT res = doc->getElementById(QStringToBSTR(name), &element);
//BSTR elemString;
if (element) {
if (SUCCEEDED(res) && element) {
//element->get_innerHTML(&elemString);
VARIANT var;
var.vt = VT_BSTR;
......
......@@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
QString utmZone;
Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
robotZ = -altitude;
} else if (frame == MAV_FRAME_LOCAL) {
} else if (frame == MAV_FRAME_LOCAL_NED) {
robotX = uas->getLocalX();
robotY = uas->getLocalY();
robotZ = uas->getLocalZ();
......@@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z)
QString utmZone;
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude;
} else if (wp->getFrame() == MAV_FRAME_LOCAL) {
} else if (wp->getFrame() == MAV_FRAME_LOCAL_NED) {
x = wp->getX();
y = wp->getY();
z = wp->getZ();
......
......@@ -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,
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;
put_int16_t_by_index(msg, 0, mag_ofs_x); // magnetometer X offset
put_int16_t_by_index(msg, 2, mag_ofs_y); // magnetometer Y offset
put_int16_t_by_index(msg, 4, mag_ofs_z); // magnetometer Z offset
put_uint8_t_by_index(msg, 6, target_system); // System ID
put_uint8_t_by_index(msg, 7, target_component); // Component ID
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_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);
}
......@@ -72,14 +85,27 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_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)
{
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
put_int16_t_by_index(msg, 0, mag_ofs_x); // magnetometer X offset
put_int16_t_by_index(msg, 2, mag_ofs_y); // magnetometer Y offset
put_int16_t_by_index(msg, 4, mag_ofs_z); // magnetometer Z offset
put_uint8_t_by_index(msg, 6, target_system); // System ID
put_uint8_t_by_index(msg, 7, target_component); // Component ID
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_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);
}
......@@ -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)
{
MAVLINK_ALIGNED_MESSAGE(msg, 8);
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
put_int16_t_by_index(msg, 0, mag_ofs_x); // magnetometer X offset
put_int16_t_by_index(msg, 2, mag_ofs_y); // magnetometer Y offset
put_int16_t_by_index(msg, 4, mag_ofs_z); // magnetometer Z offset
put_uint8_t_by_index(msg, 6, target_system); // System ID
put_uint8_t_by_index(msg, 7, target_component); // Component ID
mavlink_finalize_message_chan_send(msg, chan, 8, 219);
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 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
......@@ -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)
{
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
*/
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
*/
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
*/
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
*/
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
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);
#else
memcpy(set_mag_offsets, MAVLINK_PAYLOAD(msg), 8);
memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8);
#endif
}
......@@ -11,25 +11,25 @@ extern "C" {
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t);
static void mavlink_test_ardupilotmega(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, 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_ardupilotmega(system_id, component_id);
mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_ardupilotmega(system_id, component_id, last_msg);
}
#endif
#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;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sensor_offsets_t packet2, packet1 = {
mavlink_sensor_offsets_t packet_in = {
17.0,
963497672,
963497880,
......@@ -43,52 +43,107 @@ static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id)
19211,
19315,
};
if (sizeof(packet2) != 42) {
packet2 = packet1; // cope with alignment within the packet
}
mavlink_sensor_offsets_t packet1, packet2;
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_decode(&msg, &packet2);
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_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_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); 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_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;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mag_offsets_t packet2, packet1 = {
mavlink_set_mag_offsets_t packet_in = {
17235,
17339,
17443,
151,
218,
};
if (sizeof(packet2) != 8) {
packet2 = packet1; // cope with alignment within the packet
}
mavlink_set_mag_offsets_t packet1, packet2;
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_decode(&msg, &packet2);
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_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_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); 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_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_set_mag_offsets(system_id, component_id);
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
}
#ifdef __cplusplus
......
......@@ -5,7 +5,7 @@
#ifndef 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"
#include "mavlink.h"
......
......@@ -64,6 +64,23 @@ static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length)
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
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)
{
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);