Commit 49cebb45 authored by LM's avatar LM

Updated MAVLink, working on fixing custom widgets

parent e10ca000
......@@ -12,7 +12,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.0.0 (Alpha RC2)"
#define QGC_APPLICATION_VERSION "v. 1.0.0 (Alpha RC3)"
namespace QGC
......
......@@ -1733,11 +1733,19 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
}
}
void UAS::requestParameter(int component, int parameter)
void UAS::requestParameter(int component, const QString& parameter)
{
// Request parameter, use parameter name to request it
mavlink_message_t msg;
mavlink_param_request_read_t read;
read.param_index = parameter;
read.param_index = -1;
// Copy full param name or maximum max field size
if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
{
emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
}
memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN));
read.param_id[15] = '\0'; // Enforce null termination
read.target_system = uasId;
read.target_component = component;
mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
......
......@@ -466,7 +466,7 @@ public slots:
void requestParameters();
/** @brief Request a single parameter by index */
void requestParameter(int component, int parameter);
void requestParameter(int component, const QString& parameter);
/** @brief Set a system parameter */
void setParameter(const int component, const QString& id, const QVariant& value);
......
......@@ -246,7 +246,7 @@ public slots:
/** @brief Request all onboard parameters of all components */
virtual void requestParameters() = 0;
/** @brief Request one specific onboard parameter */
virtual void requestParameter(int component, int parameter) = 0;
virtual void requestParameter(int component, const QString& parameter) = 0;
/** @brief Write parameter to permanent storage */
virtual void writeParametersToStorage() = 0;
/** @brief Read parameter from permanent storage */
......
......@@ -244,8 +244,6 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
setupPortList();
// Set up baud rates
ui.baudRate->addItem("115200", 115200);
ui.baudRate->clear();
ui.baudRate->addItem("50", 50);
ui.baudRate->addItem("70", 70);
......
......@@ -139,10 +139,11 @@ void QGCCommandButton::endEditMode()
void QGCCommandButton::writeSettings(QSettings& settings)
{
qDebug() << "COMMAND BUTTON WRITING SETTINGS";
settings.setValue("TYPE", "COMMANDBUTTON");
settings.setValue("QGC_ACTION_BUTTON_DESCRIPTION", ui->nameLabel->text());
settings.setValue("QGC_ACTION_BUTTON_BUTTONTEXT", ui->commandButton->text());
settings.setValue("QGC_ACTION_BUTTON_ACTIONID", ui->editCommandComboBox->currentIndex());
settings.setValue("QGC_ACTION_BUTTON_ACTIONID", ui->editCommandComboBox->itemData(ui->editCommandComboBox->currentIndex()).toInt());
settings.setValue("QGC_COMMAND_BUTTON_PARAMS_VISIBLE", ui->editParamsVisibleCheckBox->isChecked());
settings.sync();
}
......@@ -155,7 +156,19 @@ void QGCCommandButton::readSettings(const QSettings& settings)
ui->nameLabel->setText(settings.value("QGC_ACTION_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->commandButton->setText(settings.value("QGC_ACTION_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
ui->editCommandComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
int commandId = settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt();
ui->editCommandComboBox->setCurrentIndex(0);
// Find combobox entry for this data
for (int i = 0; i < ui->editCommandComboBox->count(); ++i)
{
if (commandId == ui->editCommandComboBox->itemData(i).toInt())
{
ui->editCommandComboBox->setCurrentIndex(i);
}
}
ui->editParamsVisibleCheckBox->setChecked(settings.value("QGC_COMMAND_BUTTON_PARAMS_VISIBLE").toBool());
if (ui->editParamsVisibleCheckBox->isChecked()) {
ui->editParam1SpinBox->show();
......
......@@ -17,7 +17,6 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
parameterMin(0.0f),
parameterMax(0.0f),
component(0),
parameterIndex(-1),
ui(new Ui::QGCParamSlider)
{
ui->setupUi(this);
......@@ -87,8 +86,9 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas)
void QGCParamSlider::requestParameter()
{
if (parameterIndex != -1 && uas) {
uas->requestParameter(this->component, this->parameterIndex);
if (!parameterName.isEmpty() && uas)
{
uas->requestParameter(this->component, this->parameterName);
}
}
......@@ -106,7 +106,6 @@ void QGCParamSlider::selectComponent(int componentIndex)
void QGCParamSlider::selectParameter(int paramIndex)
{
parameterName = ui->editSelectParamComboBox->itemText(paramIndex);
parameterIndex = ui->editSelectParamComboBox->itemData(paramIndex).toInt();
}
void QGCParamSlider::startEditMode()
......@@ -254,7 +253,6 @@ void QGCParamSlider::writeSettings(QSettings& settings)
settings.setValue("QGC_PARAM_SLIDER_DESCRIPTION", ui->nameLabel->text());
//settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text());
settings.setValue("QGC_PARAM_SLIDER_PARAMID", parameterName);
settings.setValue("QGC_PARAM_SLIDER_PARAMINDEX", parameterIndex);
settings.setValue("QGC_PARAM_SLIDER_COMPONENTID", component);
settings.setValue("QGC_PARAM_SLIDER_MIN", ui->editMinSpinBox->value());
settings.setValue("QGC_PARAM_SLIDER_MAX", ui->editMaxSpinBox->value());
......@@ -263,11 +261,13 @@ void QGCParamSlider::writeSettings(QSettings& settings)
void QGCParamSlider::readSettings(const QSettings& settings)
{
parameterName = settings.value("QGC_PARAM_SLIDER_PARAMID").toString();
component = settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt();
ui->nameLabel->setText(settings.value("QGC_PARAM_SLIDER_DESCRIPTION").toString());
ui->editNameLabel->setText(settings.value("QGC_PARAM_SLIDER_DESCRIPTION").toString());
//settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text());
parameterIndex = settings.value("QGC_PARAM_SLIDER_PARAMINDEX", parameterIndex).toInt();
ui->editSelectParamComboBox->addItem(settings.value("QGC_PARAM_SLIDER_PARAMID").toString(), parameterIndex);
ui->editSelectParamComboBox->addItem(settings.value("QGC_PARAM_SLIDER_PARAMID").toString());
ui->editSelectParamComboBox->setCurrentIndex(ui->editSelectParamComboBox->count()-1);
ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt()), settings.value("QGC_PARAM_SLIDER_COMPONENTID").toInt());
ui->editMinSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MIN").toFloat());
ui->editMaxSpinBox->setValue(settings.value("QGC_PARAM_SLIDER_MAX").toFloat());
......
......@@ -48,7 +48,6 @@ protected:
float parameterMin;
float parameterMax;
int component; ///< ID of the MAV component to address
int parameterIndex;
double scaledInt;
void changeEvent(QEvent *e);
......
......@@ -21,6 +21,11 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
widgetTitle(title),
ui(new Ui::QGCToolWidget)
{
if (title == "Unnamed Tool")
{
widgetTitle = QString("%1 %2").arg(title).arg(QGCToolWidget::instances()->count());
}
qDebug() << "WidgetTitle" << widgetTitle;
ui->setupUi(this);
setObjectName(title);
createActions();
......@@ -42,12 +47,14 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
}
this->setWindowTitle(title);
setObjectName(title+"WIDGET");
//setObjectName(title+"WIDGET");
QList<UASInterface*> systems = UASManager::instance()->getUASList();
foreach (UASInterface* uas, systems) {
foreach (UASInterface* uas, systems)
{
UAS* newMav = dynamic_cast<UAS*>(uas);
if (newMav) {
if (newMav)
{
addUAS(uas);
}
}
......@@ -57,6 +64,8 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
QGCToolWidget::~QGCToolWidget()
{
if (mainMenuAction) delete mainMenuAction;
QGCToolWidget::instances()->remove(widgetTitle);
delete ui;
}
......@@ -94,11 +103,14 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent,
QList<QGCToolWidget*> newWidgets;
int size = settings->beginReadArray("QGC_TOOL_WIDGET_NAMES");
for (int i = 0; i < size; i++) {
for (int i = 0; i < size; i++)
{
settings->setArrayIndex(i);
QString name = settings->value("TITLE", tr("UNKNOWN WIDGET %1").arg(i)).toString();
if (!instances()->contains(name)) {
if (!instances()->contains(name))
{
qDebug() << "CREATED WIDGET:" << name;
QGCToolWidget* tool = new QGCToolWidget(name, parent);
instances()->insert(name, tool);
newWidgets.append(tool);
......@@ -113,7 +125,8 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent,
qDebug() << "NEW WIDGETS: " << newWidgets.size();
// Load individual widget items
for (int i = 0; i < newWidgets.size(); i++) {
for (int i = 0; i < newWidgets.size(); i++)
{
newWidgets.at(i)->loadSettings(*settings);
}
delete settings;
......@@ -147,29 +160,38 @@ void QGCToolWidget::loadSettings(QSettings& settings)
{
QString widgetName = getTitle();
settings.beginGroup(widgetName);
qDebug() << "LOADING FOR" << widgetName;
int size = settings.beginReadArray("QGC_TOOL_WIDGET_ITEMS");
qDebug() << "CHILDREN SIZE:" << size;
for (int j = 0; j < size; j++) {
for (int j = 0; j < size; j++)
{
settings.setArrayIndex(j);
QString type = settings.value("TYPE", "UNKNOWN").toString();
if (type != "UNKNOWN") {
if (type != "UNKNOWN")
{
QGCToolWidgetItem* item = NULL;
if (type == "COMMANDBUTTON") {
if (type == "COMMANDBUTTON")
{
item = new QGCCommandButton(this);
qDebug() << "CREATED COMMANDBUTTON";
} else if (type == "SLIDER") {
}
else if (type == "SLIDER")
{
item = new QGCParamSlider(this);
qDebug() << "CREATED PARAM SLIDER";
}
if (item) {
if (item)
{
// Configure and add to layout
addToolWidget(item);
item->readSettings(settings);
qDebug() << "Created tool widget";
}
} else {
}
else
{
qDebug() << "UNKNOWN TOOL WIDGET TYPE";
}
}
......@@ -191,14 +213,16 @@ void QGCToolWidget::storeWidgetsToSettings(QString settingsFile)
}
settings->beginWriteArray("QGC_TOOL_WIDGET_NAMES");
for (int i = 0; i < instances()->size(); ++i) {
for (int i = 0; i < instances()->size(); ++i)
{
settings->setArrayIndex(i);
settings->setValue("TITLE", instances()->values().at(i)->getTitle());
}
settings->endArray();
// Store individual widget items
for (int i = 0; i < instances()->size(); ++i) {
for (int i = 0; i < instances()->size(); ++i)
{
instances()->values().at(i)->storeSettings(*settings);
}
delete settings;
......@@ -216,15 +240,18 @@ void QGCToolWidget::storeSettings(QSettings& settings)
settings.beginGroup(widgetName);
settings.beginWriteArray("QGC_TOOL_WIDGET_ITEMS");
int k = 0; // QGCToolItem counter
for (int j = 0; j < children().size(); ++j) {
for (int j = 0; j < children().size(); ++j)
{
// Store only QGCToolWidgetItems
QGCToolWidgetItem* item = dynamic_cast<QGCToolWidgetItem*>(children().at(j));
if (item) {
if (item)
{
settings.setArrayIndex(k++);
// Store the ToolWidgetItem
item->writeSettings(settings);
}
}
qDebug() << "WROTE" << k << "SUB-WIDGETS TO SETTINGS";
settings.endArray();
settings.endGroup();
}
......@@ -232,7 +259,8 @@ void QGCToolWidget::storeSettings(QSettings& settings)
void QGCToolWidget::addUAS(UASInterface* uas)
{
UAS* newMav = dynamic_cast<UAS*>(uas);
if (newMav) {
if (newMav)
{
// FIXME Convert to list
if (mav == NULL) mav = newMav;
}
......@@ -245,9 +273,8 @@ void QGCToolWidget::contextMenuEvent (QContextMenuEvent* event)
menu.addAction(addCommandAction);
menu.addAction(setTitleAction);
menu.addAction(exportAction);
menu.addAction(importAction);
menu.addAction(deleteAction);
menu.addSeparator();
menu.addAction(addButtonAction);
menu.exec(event->globalPos());
}
......@@ -293,11 +320,7 @@ void QGCToolWidget::createActions()
importAction = new QAction(tr("Import widget"), this);
importAction->setStatusTip(tr("Import this widget from a file (current content will be removed)"));
connect(exportAction, SIGNAL(triggered()), this, SLOT(importWidget()));
addButtonAction = new QAction(tr("New MAV Action Button (Deprecated)"), this);
addButtonAction->setStatusTip(tr("Add a new action button to the tool"));
connect(addButtonAction, SIGNAL(triggered()), this, SLOT(addAction()));
connect(importAction, SIGNAL(triggered()), this, SLOT(importWidget()));
}
QMap<QString, QGCToolWidget*>* QGCToolWidget::instances()
......@@ -317,7 +340,8 @@ QList<QGCToolWidgetItem*>* QGCToolWidget::itemList()
void QGCToolWidget::addParam()
{
QGCParamSlider* slider = new QGCParamSlider(this);
if (ui->hintLabel) {
if (ui->hintLabel)
{
ui->hintLabel->deleteLater();
ui->hintLabel = NULL;
}
......@@ -328,7 +352,8 @@ void QGCToolWidget::addParam()
void QGCToolWidget::addCommand()
{
QGCCommandButton* button = new QGCCommandButton(this);
if (ui->hintLabel) {
if (ui->hintLabel)
{
ui->hintLabel->deleteLater();
ui->hintLabel = NULL;
}
......@@ -338,7 +363,8 @@ void QGCToolWidget::addCommand()
void QGCToolWidget::addToolWidget(QGCToolWidgetItem* widget)
{
if (ui->hintLabel) {
if (ui->hintLabel)
{
ui->hintLabel->deleteLater();
ui->hintLabel = NULL;
}
......@@ -371,38 +397,44 @@ const QString QGCToolWidget::getTitle()
void QGCToolWidget::setTitle()
{
QDockWidget* parent = dynamic_cast<QDockWidget*>(this->parentWidget());
if (parent) {
if (parent)
{
bool ok;
QString text = QInputDialog::getText(this, tr("QInputDialog::getText()"),
QString text = QInputDialog::getText(this, tr("Enter Widget Title"),
tr("Widget title:"), QLineEdit::Normal,
parent->windowTitle(), &ok);
if (ok && !text.isEmpty()) {
QSettings settings;
settings.beginGroup(parent->windowTitle());
settings.remove("");
settings.endGroup();
parent->setWindowTitle(text);
setWindowTitle(text);
storeWidgetsToSettings();
emit titleChanged(text);
if (mainMenuAction) mainMenuAction->setText(text);
if (ok && !text.isEmpty())
{
setTitle(text);
}
}
}
void QGCToolWidget::setWindowTitle(const QString& title)
{
// Sets title and calls setWindowTitle on QWidget
setTitle(title);
}
void QGCToolWidget::setTitle(QString title)
{
widgetTitle = title;
// Remove references to old title
QDockWidget* parent = dynamic_cast<QDockWidget*>(this->parentWidget());
if (parent) {
if (parent)
{
QSettings settings;
settings.beginGroup(parent->windowTitle());
settings.beginGroup(widgetTitle);
settings.remove("");
settings.endGroup();
parent->setWindowTitle(title);
}
setWindowTitle(title);
if (instances()->contains(widgetTitle)) instances()->remove(widgetTitle);
// Switch to new title
widgetTitle = title;
if (!instances()->contains(title)) instances()->insert(title, this);
QWidget::setWindowTitle(title);
if (parent) parent->setWindowTitle(title);
storeWidgetsToSettings();
emit titleChanged(title);
......
......@@ -19,7 +19,7 @@ class QGCToolWidget : public QWidget
Q_OBJECT
public:
explicit QGCToolWidget(const QString& title, QWidget *parent = 0);
explicit QGCToolWidget(const QString& title=QString("Unnamed Tool"), QWidget *parent = 0);
~QGCToolWidget();
/** @brief Factory method to instantiate all tool widgets */
......@@ -61,7 +61,6 @@ signals:
protected:
QAction* addParamAction;
QAction* addButtonAction;
QAction* addCommandAction;
QAction* setTitleAction;
QAction* deleteAction;
......@@ -73,6 +72,7 @@ protected:
QMap<int, Qt::DockWidgetArea> dockWidgetArea; ///< Dock widget area desired by this widget
QMap<int, bool> viewVisible; ///< Visibility in one view
QString widgetTitle;
static int instanceCount; ///< Number of instances around
void contextMenuEvent(QContextMenuEvent* event);
void createActions();
......@@ -87,6 +87,7 @@ protected slots:
void addCommand();
void setTitle();
void setTitle(QString title);
void setWindowTitle(const QString& title);
private:
......
// MESSAGE AP_ADC PACKING
#define MAVLINK_MSG_ID_AP_ADC 153
typedef struct __mavlink_ap_adc_t
{
uint16_t adc1; ///< ADC output 1
uint16_t adc2; ///< ADC output 2
uint16_t adc3; ///< ADC output 3
uint16_t adc4; ///< ADC output 4
uint16_t adc5; ///< ADC output 5
uint16_t adc6; ///< ADC output 6
} mavlink_ap_adc_t;
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
#define MAVLINK_MSG_ID_153_LEN 12
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
/**
* @brief Pack a ap_adc 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 adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message(msg, system_id, component_id, 12, 188);
}
/**
* @brief Pack a ap_adc 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 adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 188);
}
/**
* @brief Encode a ap_adc 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 ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12, 188);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12, 188);
#endif
}
#endif
// MESSAGE AP_ADC UNPACKING
/**
* @brief Get field adc1 from ap_adc message
*
* @return ADC output 1
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field adc2 from ap_adc message
*
* @return ADC output 2
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field adc3 from ap_adc message
*
* @return ADC output 3
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field adc4 from ap_adc message
*
* @return ADC output 4
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field adc5 from ap_adc message
*
* @return ADC output 5
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field adc6 from ap_adc message
*
* @return ADC output 6
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
/**
* @brief Decode a ap_adc message into a struct
*
* @param msg The message to decode
* @param ap_adc C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
#else
memcpy(ap_adc, _MAV_PAYLOAD(msg), 12);
#endif
}
// MESSAGE MEMINFO PACKING
#define MAVLINK_MSG_ID_MEMINFO 152
typedef struct __mavlink_meminfo_t
{
uint16_t brkval; ///< heap top
uint16_t freemem; ///< free memory
} mavlink_meminfo_t;
#define MAVLINK_MSG_ID_MEMINFO_LEN 4
#define MAVLINK_MSG_ID_152_LEN 4
#define MAVLINK_MESSAGE_INFO_MEMINFO { \
"MEMINFO", \
2, \
{ { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
{ "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
} \
}
/**
* @brief Pack a meminfo 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 brkval heap top
* @param freemem free memory
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t brkval, uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
memcpy(_MAV_PAYLOAD(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message(msg, system_id, component_id, 4, 208);
}
/**
* @brief Pack a meminfo 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 brkval heap top
* @param freemem free memory
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t brkval,uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
memcpy(_MAV_PAYLOAD(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208);
}
/**
* @brief Encode a meminfo 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 meminfo C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
{
return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem);
}
/**
* @brief Send a meminfo message
* @param chan MAVLink channel to send the message
*
* @param brkval heap top
* @param freemem free memory
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, 4, 208);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, 4, 208);
#endif
}
#endif
// MESSAGE MEMINFO UNPACKING
/**
* @brief Get field brkval from meminfo message
*
* @return heap top
*/
static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field freemem from meminfo message
*
* @return free memory
*/
static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Decode a meminfo message into a struct
*
* @param msg The message to decode
* @param meminfo C-struct to decode the message contents into
*/
static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo)
{
#if MAVLINK_NEED_BYTE_SWAP
meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg);
meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg);
#else
memcpy(meminfo, _MAV_PAYLOAD(msg), 4);
#endif
}
......@@ -140,10 +140,110 @@ static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_meminfo(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_meminfo_t packet_in = {
17235,
17339,
};
mavlink_meminfo_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.brkval = packet_in.brkval;
packet1.freemem = packet_in.freemem;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_pack(system_id, component_id, &msg , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_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_meminfo_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_send(MAVLINK_COMM_1 , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_ap_adc(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_ap_adc_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
};
mavlink_ap_adc_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.adc1 = packet_in.adc1;
packet1.adc2 = packet_in.adc2;
packet1.adc3 = packet_in.adc3;
packet1.adc4 = packet_in.adc4;
packet1.adc5 = packet_in.adc5;
packet1.adc6 = packet_in.adc6;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_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_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_send(MAVLINK_COMM_1 , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_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, mavlink_message_t *last_msg)
{
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
mavlink_test_meminfo(system_id, component_id, last_msg);
mavlink_test_ap_adc(system_id, component_id, last_msg);
}
#ifdef __cplusplus
......
......@@ -5,9 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 16:29:29 2011"
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:47:31 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
......@@ -5,9 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 17:05:00 2011"
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:48:20 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
......@@ -214,7 +214,13 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
break;
case MAVLINK_PARSE_STATE_GOT_STX:
if (status->msg_received)
if (status->msg_received
/* Support shorter buffers than the
default maximum packet size */
#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
|| c > MAVLINK_MAX_PAYLOAD_LEN
#endif
)
{
status->buffer_overrun++;
status->parse_error++;
......
#ifndef MAVLINK_TYPES_H_
#define MAVLINK_TYPES_H_
#include <inttypes.h>
enum MAV_ACTION
{
MAV_ACTION_HOLD = 0,
......@@ -49,7 +51,10 @@ enum MAV_ACTION
MAV_ACTION_NB ///< Number of MAV actions
};
#ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful!
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
#endif
#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
......
......@@ -5,9 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 16:30:02 2011"
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:47:47 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 9
#endif // MAVLINK_VERSION_H
......@@ -5,9 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 17:05:00 2011"
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:47:55 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
#endif // MAVLINK_VERSION_H
......@@ -48,8 +48,10 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
uint8_t chan, uint8_t length, uint8_t crc_extra);
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length, uint8_t crc_extra);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
uint8_t length, uint8_t crc_extra);
#endif
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length);
......
......@@ -5,9 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 16:30:09 2011"
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:48:02 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/** @file
* @brief MAVLink comm protocol built from test.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#include "version.h"
#include "test.h"
#endif // MAVLINK_H
/** @file
* @brief MAVLink comm protocol generated from test.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef TEST_H
#define TEST_H
#ifdef __cplusplus
extern "C" {
#endif
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {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}}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_TEST
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 3
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 3
#endif
// ENUM DEFINITIONS
// MESSAGE DEFINITIONS
#include "./mavlink_msg_test_types.h"
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // TEST_H
/** @file
* @brief MAVLink comm protocol testsuite generated from test.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef TEST_TESTSUITE_H
#define TEST_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_test(system_id, component_id, last_msg);
}
#endif
static void mavlink_test_test_types(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_test_types_t packet_in = {
93372036854775807ULL,
93372036854776311LL,
235.0,
{ 93372036854777319, 93372036854777320, 93372036854777321 },
{ 93372036854778831, 93372036854778832, 93372036854778833 },
{ 627.0, 628.0, 629.0 },
963502456,
963502664,
745.0,
{ 963503080, 963503081, 963503082 },
{ 963503704, 963503705, 963503706 },
{ 941.0, 942.0, 943.0 },
24723,
24827,
{ 24931, 24932, 24933 },
{ 25243, 25244, 25245 },
'E',
"FGHIJKLMN",
198,
9,
{ 76, 77, 78 },
{ 21, 22, 23 },
};
mavlink_test_types_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.u64 = packet_in.u64;
packet1.s64 = packet_in.s64;
packet1.d = packet_in.d;
packet1.u32 = packet_in.u32;
packet1.s32 = packet_in.s32;
packet1.f = packet_in.f;
packet1.u16 = packet_in.u16;
packet1.s16 = packet_in.s16;
packet1.c = packet_in.c;
packet1.u8 = packet_in.u8;
packet1.s8 = packet_in.s8;
memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3);
memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3);
memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3);
memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3);
memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3);
memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3);
memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3);
memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3);
memcpy(packet1.s, packet_in.s, sizeof(char)*10);
memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3);
memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_test_types_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
mavlink_msg_test_types_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
mavlink_msg_test_types_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_test_types_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_test_types_send(MAVLINK_COMM_1 , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array );
mavlink_msg_test_types_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_test(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_test_types(system_id, component_id, last_msg);
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // TEST_TESTSUITE_H
/** @file
* @brief MAVLink comm protocol built from test.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 16:29:55 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#endif // MAVLINK_VERSION_H
......@@ -5,9 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Fri Sep 2 17:04:49 2011"
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:48:20 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
......@@ -212,7 +212,7 @@
<field type="uint8_t[32]" name="descriptor">Descriptor</field>
<field type="float" name="response">Harris operator response at this location</field>
</message>
<message id="200" name="ATTITUDE_CONTROL">
<message id="200" name="ATTITUDE_CONTROL">
<field type="uint8_t" name="target">The system to be controlled</field>
<field type="float" name="roll">roll</field>
<field type="float" name="pitch">pitch</field>
......
<?xml version='1.0'?>
<mavlink>
<version>3</version>
<messages>
<version>3</version>
<messages>
<message id="0" name="TEST_TYPES">
<description>Test all field types</description>
<field type="char" name="c">char</field>
<field type="char[10]" name="s">string</field>
<field type="char" name="c">char</field>
<field type="char[10]" name="s">string</field>
<field type="uint8_t" name="u8">uint8_t</field>
<field type="uint16_t" name="u16">uint16_t</field>
<field type="uint32_t" name="u32" print_format="0x%08x">uint32_t</field>
<field print_format="0x%08x" type="uint32_t" name="u32">uint32_t</field>
<field type="uint64_t" name="u64">uint64_t</field>
<field type="int8_t" name="s8">int8_t</field>
<field type="int16_t" name="s16">int16_t</field>
......@@ -27,5 +27,5 @@
<field type="float[3]" name="f_array">float_array</field>
<field type="double[3]" name="d_array">double_array</field>
</message>
</messages>
</messages>
</mavlink>
......@@ -86,7 +86,7 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess
&tx_msg,
pm.param_names[i],
pm.param_values[i],
MAV_DATA_TYPE_FLOAT,
MAVLINK_TYPE_FLOAT,
pm.size,
i);
mavlink_missionlib_send_message(&tx_msg);
......@@ -94,7 +94,7 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess
mavlink_msg_param_value_send(MAVLINK_COMM_0,
pm.param_names[i],
pm.param_values[i],
MAV_DATA_TYPE_FLOAT,
MAVLINK_TYPE_FLOAT,
pm.size,
i);
#endif
......@@ -133,7 +133,7 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess
&tx_msg,
pm.param_names[pm.next_param],
pm.param_values[pm.next_param],
MAV_DATA_TYPE_FLOAT,
MAVLINK_TYPE_FLOAT,
pm.size,
pm.next_param);
mavlink_missionlib_send_message(&tx_msg);
......
......@@ -67,9 +67,6 @@ mavlink_system_t mavlink_system;
/* 2: Include actual protocol, REQUIRES mavlink_system */
#include "mavlink.h"
/* 3: Include MAVLink data structures */
#include "mavlink_data.h"
/* 3: Define waypoint helper functions */
void mavlink_wpm_send_message(mavlink_message_t* msg);
void mavlink_wpm_send_gcs_string(const char* string);
......@@ -184,6 +181,9 @@ int main(int argc, char* argv[])
mavlink_system.compid = 20;
mavlink_pm_reset_params(&pm);
int32_t ground_distance;
uint32_t time_ms;
// Create socket
......@@ -246,17 +246,17 @@ int main(int argc, char* argv[])
bytes_sent = 0;
/* Send Heartbeat */
mavlink_msg_heartbeat_pack(mavlink_system.sysid, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, 0, 0, 0, 0, 0);
mavlink_msg_heartbeat_pack(mavlink_system.sysid, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, 0, 0, 0);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
/* Send Status */
mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED, 0, MAV_STATE_ACTIVE, 500, 7500, 0, 0, 0, 0, 0, 0, 0);
mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE, 500, 7500, 0, 0, 0, 0, 0, 0, 0, 0);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
/* Send Local Position */
mavlink_msg_local_position_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(),
mavlink_msg_local_position_ned_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(),
position[0], position[1], position[2],
position[3], position[4], position[5]);
len = mavlink_msg_to_send_buffer(buf, &msg);
......@@ -265,7 +265,7 @@ int main(int argc, char* argv[])
/* Send global position */
if (hilEnabled)
{
mavlink_msg_global_position_int_pack(mavlink_system.sysid, 200, &msg, latitude, longitude, altitude, speedx, speedy, speedz, (yaw/M_PI)*180*100);
mavlink_msg_global_position_int_pack(mavlink_system.sysid, 200, &msg, time_ms, latitude, longitude, altitude, ground_distance, speedx, speedy, speedz, (yaw/M_PI)*180*100);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
}
......
This diff is collapsed.
......@@ -64,9 +64,9 @@ enum MAVLINK_WPM_CODES
struct mavlink_wpm_storage {
mavlink_waypoint_t waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Currently active waypoints
mavlink_mission_item_t waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Currently active waypoints
#ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE
mavlink_waypoint_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints
mavlink_mission_item_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT]; ///< Receive buffer for next waypoints
#endif
uint16_t size;
uint16_t max_size;
......
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