Commit dd93ea7c authored by Lionel Heng's avatar Lionel Heng

Merge branch 'master' of github.com:mavlink/qgroundcontrol

parents 15fa5652 b1044aa7
...@@ -95,7 +95,7 @@ void JoystickInput::init() ...@@ -95,7 +95,7 @@ void JoystickInput::init()
// Wait for joysticks if none is connected // Wait for joysticks if none is connected
while (numJoysticks == 0) while (numJoysticks == 0)
{ {
MG::SLEEP::msleep(800); QGC::SLEEP::msleep(800);
// INITIALIZE SDL Joystick support // INITIALIZE SDL Joystick support
if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0)
{ {
......
...@@ -94,7 +94,9 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -94,7 +94,9 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
simulation(new QGCFlightGearLink(this)), simulation(new QGCFlightGearLink(this)),
isLocalPositionKnown(false), isLocalPositionKnown(false),
isGlobalPositionKnown(false), isGlobalPositionKnown(false),
systemIsArmed(false) systemIsArmed(false),
nedPosGlobalOffset(0,0,0),
nedAttGlobalOffset(0,0,0)
{ {
for (unsigned int i = 0; i<255;++i) for (unsigned int i = 0; i<255;++i)
{ {
...@@ -440,7 +442,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -440,7 +442,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f) if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
&& (lpVoltage < tickVoltage)) && (lpVoltage < tickVoltage))
{ {
GAudioOutput::instance()->say(QString("voltage warning: %1 volt").arg(lpVoltage, 2, 'f', 0, QChar(' '))); GAudioOutput::instance()->say(QString("voltage warning: %1 volt").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
lastTickVoltageValue = tickLowpassVoltage; lastTickVoltageValue = tickLowpassVoltage;
} }
...@@ -528,6 +530,18 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -528,6 +530,18 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
break; break;
case MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET:
{
mavlink_local_position_ned_system_global_offset_t offset;
mavlink_msg_local_position_ned_system_global_offset_decode(&message, &offset);
nedPosGlobalOffset.setX(offset.x);
nedPosGlobalOffset.setY(offset.y);
nedPosGlobalOffset.setZ(offset.z);
nedAttGlobalOffset.setX(offset.roll);
nedAttGlobalOffset.setY(offset.pitch);
nedAttGlobalOffset.setZ(offset.yaw);
}
break;
case MAVLINK_MSG_ID_HIL_CONTROLS: case MAVLINK_MSG_ID_HIL_CONTROLS:
{ {
mavlink_hil_controls_t hil; mavlink_hil_controls_t hil;
......
...@@ -33,8 +33,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -33,8 +33,8 @@ This file is part of the QGROUNDCONTROL project
#define _UAS_H_ #define _UAS_H_
#include "UASInterface.h" #include "UASInterface.h"
#include "MG.h"
#include <MAVLinkProtocol.h> #include <MAVLinkProtocol.h>
#include <QVector3D>
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCFlightGearLink.h" #include "QGCFlightGearLink.h"
...@@ -53,7 +53,8 @@ public: ...@@ -53,7 +53,8 @@ public:
UAS(MAVLinkProtocol* protocol, int id = 0); UAS(MAVLinkProtocol* protocol, int id = 0);
~UAS(); ~UAS();
enum BatteryType { enum BatteryType
{
NICD = 0, NICD = 0,
NIMH = 1, NIMH = 1,
LIION = 2, LIION = 2,
...@@ -80,7 +81,8 @@ public: ...@@ -80,7 +81,8 @@ public:
/** @brief Get the unique system id */ /** @brief Get the unique system id */
int getUASID() const; int getUASID() const;
/** @brief Get the airframe */ /** @brief Get the airframe */
int getAirframe() const { int getAirframe() const
{
return airframe; return airframe;
} }
/** @brief Get the components */ /** @brief Get the components */
...@@ -107,13 +109,16 @@ public: ...@@ -107,13 +109,16 @@ public:
{ {
return localZ; return localZ;
} }
double getLatitude() const { double getLatitude() const
{
return latitude; return latitude;
} }
double getLongitude() const { double getLongitude() const
{
return longitude; return longitude;
} }
double getAltitude() const { double getAltitude() const
{
return altitude; return altitude;
} }
virtual bool localPositionKnown() const virtual bool localPositionKnown() const
...@@ -125,24 +130,39 @@ public: ...@@ -125,24 +130,39 @@ public:
return isGlobalPositionKnown; return isGlobalPositionKnown;
} }
double getRoll() const { double getRoll() const
{
return roll; return roll;
} }
double getPitch() const { double getPitch() const
{
return pitch; return pitch;
} }
double getYaw() const { double getYaw() const
{
return yaw; return yaw;
} }
bool getSelected() const; bool getSelected() const;
QVector3D getNedPosGlobalOffset() const
{
return nedPosGlobalOffset;
}
QVector3D getNedAttGlobalOffset() const
{
return nedAttGlobalOffset;
}
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay getOverlay() { px::GLOverlay getOverlay()
{
QMutexLocker locker(&overlayMutex); QMutexLocker locker(&overlayMutex);
return overlay; return overlay;
} }
px::GLOverlay getOverlay(qreal& receivedTimestamp) { px::GLOverlay getOverlay(qreal& receivedTimestamp)
{
receivedTimestamp = receivedOverlayTimestamp; receivedTimestamp = receivedOverlayTimestamp;
QMutexLocker locker(&overlayMutex); QMutexLocker locker(&overlayMutex);
return overlay; return overlay;
...@@ -315,6 +335,8 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -315,6 +335,8 @@ protected: //COMMENTS FOR TEST UNIT
bool isLocalPositionKnown; ///< If the local position has been received for this MAV bool isLocalPositionKnown; ///< If the local position has been received for this MAV
bool isGlobalPositionKnown; ///< If the global position has been received for this MAV bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
bool systemIsArmed; ///< If the system is armed bool systemIsArmed; ///< If the system is armed
QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
public: public:
/** @brief Set the current battery type */ /** @brief Set the current battery type */
......
...@@ -279,7 +279,7 @@ void HUD::setActiveUAS(UASInterface* uas) ...@@ -279,7 +279,7 @@ void HUD::setActiveUAS(UASInterface* uas)
// Now connect the new UAS // Now connect the new UAS
// Setup communication // Setup communication
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
connect(this->uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,int,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,int,double, double, double, quint64)));
connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int))); connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString))); connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
...@@ -854,6 +854,8 @@ void HUD::paintHUD() ...@@ -854,6 +854,8 @@ void HUD::paintHUD()
// PITCH // PITCH
paintPitchLines(att.y(), &painter); paintPitchLines(att.y(), &painter);
painter.translate(0, -(-att.y()/(float)M_PI)* -180.0f * refToScreenY(1.8f));
painter.rotate(-(att.x()/M_PI)* -180.0f);
} }
painter.end(); painter.end();
......
...@@ -99,8 +99,8 @@ ...@@ -99,8 +99,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>232</width> <width>219</width>
<height>516</height> <height>475</height>
</rect> </rect>
</property> </property>
</widget> </widget>
...@@ -109,7 +109,7 @@ ...@@ -109,7 +109,7 @@
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="0" column="4" rowspan="2"> <item row="0" column="4" rowspan="4">
<widget class="QGroupBox" name="diagramGroupBox"> <widget class="QGroupBox" name="diagramGroupBox">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
...@@ -134,21 +134,21 @@ ...@@ -134,21 +134,21 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="0"> <item row="3" column="0">
<widget class="QCheckBox" name="shortNameCheckBox"> <widget class="QCheckBox" name="shortNameCheckBox">
<property name="text"> <property name="text">
<string>Short Names</string> <string>Short Names</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2" colspan="2"> <item row="3" column="2" colspan="2">
<widget class="QPushButton" name="recolorButton"> <widget class="QPushButton" name="recolorButton">
<property name="text"> <property name="text">
<string>Recolor</string> <string>Recolor</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="1"> <item row="3" column="1">
<spacer name="horizontalSpacer"> <spacer name="horizontalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
...@@ -161,6 +161,15 @@ ...@@ -161,6 +161,15 @@
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="2" column="0" colspan="4">
<widget class="QComboBox" name="uasSelectionBox">
<item>
<property name="text">
<string>All MAVs</string>
</property>
</item>
</widget>
</item>
</layout> </layout>
</widget> </widget>
<resources/> <resources/>
......
...@@ -146,6 +146,7 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent ...@@ -146,6 +146,7 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent
updateTimer->setInterval(updateInterval); updateTimer->setInterval(updateInterval);
connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh())); connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh()));
connect(ui.uasSelectionBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectActiveSystem(int)));
readSettings(); readSettings();
} }
...@@ -159,6 +160,17 @@ LinechartWidget::~LinechartWidget() ...@@ -159,6 +160,17 @@ LinechartWidget::~LinechartWidget()
listedCurves = NULL; listedCurves = NULL;
} }
void LinechartWidget::selectActiveSystem(int mav)
{
// -1: Unitialized, 0: all
if (mav != selectedMAV && (selectedMAV != -1))
{
// Delete all curves
// FIXME
}
selectedMAV = mav;
}
void LinechartWidget::selectAllCurves(bool all) void LinechartWidget::selectAllCurves(bool all)
{ {
QMap<QString, QLabel*>::iterator i; QMap<QString, QLabel*>::iterator i;
......
...@@ -105,11 +105,8 @@ public slots: ...@@ -105,11 +105,8 @@ public slots:
/** @brief Stop automatic updates once hidden */ /** @brief Stop automatic updates once hidden */
void hideEvent(QHideEvent* event); void hideEvent(QHideEvent* event);
void setActive(bool active); void setActive(bool active);
void setActiveSystem(int systemid) /** @brief Select one MAV for curve display */
{ void selectActiveSystem(int mav);
selectedMAV = systemid;
}
/** @brief Set the number of values to average over */ /** @brief Set the number of values to average over */
void setAverageWindow(int windowSize); void setAverageWindow(int windowSize);
/** @brief Start logging to file */ /** @brief Start logging to file */
......
...@@ -63,36 +63,40 @@ void Linecharts::hideEvent(QHideEvent* event) ...@@ -63,36 +63,40 @@ void Linecharts::hideEvent(QHideEvent* event)
void Linecharts::selectSystem(int systemid) void Linecharts::selectSystem(int systemid)
{ {
QWidget* prevWidget = currentWidget(); // QWidget* prevWidget = currentWidget();
if (prevWidget) // if (prevWidget)
{ // {
LinechartWidget* chart = dynamic_cast<LinechartWidget*>(prevWidget); // LinechartWidget* chart = dynamic_cast<LinechartWidget*>(prevWidget);
if (chart) // if (chart)
{ // {
chart->setActive(false); // chart->setActive(false);
chart->setActiveSystem(systemid); // chart->setActiveSystem(systemid);
} // }
} // }
QWidget* widget = plots.value(systemid, NULL); // QWidget* widget = plots.value(systemid, NULL);
if (widget) // if (widget)
{ // {
setCurrentWidget(widget); // setCurrentWidget(widget);
LinechartWidget* chart = dynamic_cast<LinechartWidget*>(widget); // LinechartWidget* chart = dynamic_cast<LinechartWidget*>(widget);
if (chart) // if (chart)
{ // {
chart->setActive(true); // chart->setActive(true);
chart->setActiveSystem(systemid); // chart->setActiveSystem(systemid);
} // }
} // }
} }
void Linecharts::addSystem(UASInterface* uas) void Linecharts::addSystem(UASInterface* uas)
{ {
if (!plots.contains(uas->getUASID())) // FIXME Add removeSystem() call
// Compatibility hack
int uasid = 0; /*uas->getUASID()*/
if (!plots.contains(uasid))
{ {
LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this); LinechartWidget* widget = new LinechartWidget(uasid, this);
addWidget(widget); addWidget(widget);
plots.insert(uas->getUASID(), widget); plots.insert(uasid, widget);
// Connect valueChanged signals // Connect valueChanged signals
connect(uas, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), widget, SLOT(appendData(int,QString,QString,quint8,quint64))); connect(uas, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), widget, SLOT(appendData(int,QString,QString,quint8,quint64)));
...@@ -107,10 +111,10 @@ void Linecharts::addSystem(UASInterface* uas) ...@@ -107,10 +111,10 @@ void Linecharts::addSystem(UASInterface* uas)
connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString))); connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString)));
// Set system active if this is the only system // Set system active if this is the only system
if (active) // if (active)
{ // {
if (plots.size() == 1) // if (plots.size() == 1)
{ // {
// FIXME XXX HACK // FIXME XXX HACK
// Connect generic sources // Connect generic sources
for (int i = 0; i < genericSources.count(); ++i) for (int i = 0; i < genericSources.count(); ++i)
...@@ -126,10 +130,11 @@ void Linecharts::addSystem(UASInterface* uas) ...@@ -126,10 +130,11 @@ void Linecharts::addSystem(UASInterface* uas)
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64))); connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64)));
} }
// Select system // Select system
selectSystem(uas->getUASID()); widget->setActive(true);
//widget->selectActiveSystem(0);
} }
} // }
} // }
} }
void Linecharts::addSource(QObject* obj) void Linecharts::addSource(QObject* obj)
...@@ -149,4 +154,4 @@ void Linecharts::addSource(QObject* obj) ...@@ -149,4 +154,4 @@ void Linecharts::addSource(QObject* obj)
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint64,quint64))); connect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint64,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64))); connect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64)));
} }
} }
\ No newline at end of file
...@@ -285,6 +285,14 @@ Pixhawk3DWidget::localPositionChanged(UASInterface* uas, ...@@ -285,6 +285,14 @@ Pixhawk3DWidget::localPositionChanged(UASInterface* uas,
return; return;
} }
// Add offset
UAS* mav = qobject_cast<UAS*>(uas);
float offX = mav->getNedPosGlobalOffset().x();
float offY = mav->getNedPosGlobalOffset().y();
float offZ = mav->getNedPosGlobalOffset().z();
float offYaw = mav->getNedAttGlobalOffset().z();
// update system position // update system position
m3DWidget->systemGroup(systemId)->position()->setPosition(osg::Vec3d(y, x, -z)); m3DWidget->systemGroup(systemId)->position()->setPosition(osg::Vec3d(y, x, -z));
} }
......
This diff is collapsed.
...@@ -3123,6 +3123,61 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma ...@@ -3123,6 +3123,61 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_local_position_ned_system_global_offset(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_local_position_ned_system_global_offset_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
};
mavlink_local_position_ned_system_global_offset_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_local_position_ned_system_global_offset_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_local_position_ned_system_global_offset_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_local_position_ned_system_global_offset_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_hil_state(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_hil_state(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_message_t msg; mavlink_message_t msg;
...@@ -3336,17 +3391,17 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m ...@@ -3336,17 +3391,17 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m
mavlink_optical_flow_t packet_in = { mavlink_optical_flow_t packet_in = {
93372036854775807ULL, 93372036854775807ULL,
73.0, 73.0,
17859, 101.0,
17963, 129.0,
53, 65,
120, 132,
}; };
mavlink_optical_flow_t packet1, packet2; mavlink_optical_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1)); memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec; packet1.time_usec = packet_in.time_usec;
packet1.ground_distance = packet_in.ground_distance;
packet1.flow_x = packet_in.flow_x; packet1.flow_x = packet_in.flow_x;
packet1.flow_y = packet_in.flow_y; packet1.flow_y = packet_in.flow_y;
packet1.ground_distance = packet_in.ground_distance;
packet1.sensor_id = packet_in.sensor_id; packet1.sensor_id = packet_in.sensor_id;
packet1.quality = packet_in.quality; packet1.quality = packet_in.quality;
...@@ -3942,6 +3997,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink ...@@ -3942,6 +3997,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vfr_hud(system_id, component_id, last_msg); mavlink_test_vfr_hud(system_id, component_id, last_msg);
mavlink_test_command_long(system_id, component_id, last_msg); mavlink_test_command_long(system_id, component_id, last_msg);
mavlink_test_command_ack(system_id, component_id, last_msg); mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_local_position_ned_system_global_offset(system_id, component_id, last_msg);
mavlink_test_hil_state(system_id, component_id, last_msg); mavlink_test_hil_state(system_id, component_id, last_msg);
mavlink_test_hil_controls(system_id, component_id, last_msg); mavlink_test_hil_controls(system_id, component_id, last_msg);
mavlink_test_hil_rc_inputs_raw(system_id, component_id, last_msg); mavlink_test_hil_rc_inputs_raw(system_id, component_id, last_msg);
......
...@@ -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 "Thu Feb 9 16:35:38 2012" #define MAVLINK_BUILD_DATE "Sat Feb 25 17:32:04 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
...@@ -15,21 +15,10 @@ ...@@ -15,21 +15,10 @@
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
#if (defined __GNUC__) || (defined _MSC_VER) || (defined __MINGW32__) || (defined __WATCOMC__) || (defined __CMB__) || (defined __BORLANDC__) || (defined __clang__)
#define MAVLINK_EXTENDED_MESSAGES_ENABLED
#endif
// EXTENDED message definition - the extended message set is compatible to standard MAVLink message passing
// but does NOT have to be supported by the platform. The extended message set will NOT consume
// any memory if the messages are not explicitely used
#ifdef MAVLINK_EXTENDED_MESSAGES_ENABLED
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14 #define MAVLINK_EXTENDED_HEADER_LEN 14
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
#endif
typedef struct param_union { typedef struct param_union {
union { union {
...@@ -62,13 +51,12 @@ typedef struct __mavlink_message { ...@@ -62,13 +51,12 @@ typedef struct __mavlink_message {
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t; } mavlink_message_t;
#ifdef MAVLINK_EXTENDED_MESSAGES_ENABLED
typedef struct __mavlink_extended_message { typedef struct __mavlink_extended_message {
mavlink_message_t base_msg; mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t; } mavlink_extended_message_t;
#endif
typedef enum { typedef enum {
......
...@@ -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 "Thu Feb 9 16:35:38 2012" #define MAVLINK_BUILD_DATE "Sat Feb 25 17:32:04 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
...@@ -1367,42 +1367,16 @@ ...@@ -1367,42 +1367,16 @@
<field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field> <field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field>
<field type="uint8_t" name="result">See MAV_RESULT enum</field> <field type="uint8_t" name="result">See MAV_RESULT enum</field>
</message> </message>
<!-- <message id="89" name="LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET">
<message id="80" name="MISSION_ITEM"> <description>The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
<description>One mission element following the MAV_CMD enumeration</description> <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="uint8_t" name="target_system">System ID</field> <field type="float" name="x">X Position</field>
<field type="uint8_t" name="target_component">Component ID</field> <field type="float" name="y">Y Position</field>
<field type="uint16_t" name="id">ID</field> <field type="float" name="z">Z Position</field>
<field type="uint16_t" name="id">Total count (size of total mission)</field> <field type="float" name="roll">Roll</field>
<field type="uint8_t" name="frame">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field> <field type="float" name="pitch">Pitch</field>
<field type="uint8_t" name="command">The scheduled action for the MISSION. see MAV_COMMAND in common.xml MAVLink specs</field> <field type="float" name="yaw">Yaw</field>
<field type="uint8_t" name="current">false:0, true:1</field>
<field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
<field type="float" name="param1">PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters</field>
<field type="float" name="param2">PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
<field type="float" name="param3">PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
<field type="float" name="param4">PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
<field type="float" name="x">PARAM5 / local: x position, global: latitude</field>
<field type="float" name="y">PARAM6 / y position: global: longitude</field>
<field type="float" name="z">PARAM7 / z position: global: altitude</field>
</message> </message>
<message id="81" name="MISSION_ACK">
<description>ACK / NACK for one mission element or a whole mission</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="mission_status"></field>
<field type="uint16_t" name="begin_item"></field>
<field type="uint16_t" name="end_item"></field>
<field type="uint8_t" name="packet_seq"></field>
</message>
<message id="82" name="MISSION_REQUEST">
<description>One mission element following the MAV_CMD enumeration</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="mission_command">Command id: 0: read whole mission, 1: read mission from begin to end, 2: write mission items from begin to end, 3: clear mission.</field>
<field type="uint16_t" name="begin_item"></field>
<field type="uint16_t" name="end_item"></field>
</message> -->
<message id="90" name="HIL_STATE"> <message id="90" name="HIL_STATE">
<description>Sent from simulation to autopilot. This packet is useful for high throughput <description>Sent from simulation to autopilot. This packet is useful for high throughput
applications such as hardware in the loop simulations. applications such as hardware in the loop simulations.
......
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