diff --git a/src/configuration.h b/src/configuration.h index 3872b2d673e16058a27bc25f052b7b4b7d7e4a42..4ccd351b176422c1240e9c179ff29b3e6ce6d0da 100644 --- a/src/configuration.h +++ b/src/configuration.h @@ -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 diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 97487f12e20d599b27883d53bba88f461ccdf3b1..5429ae6b7bd4cf681382c6bda75280f854d1796d 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -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); diff --git a/src/uas/UAS.h b/src/uas/UAS.h index a0051b76f7288250f4f22184be76df1d02aefe76..e9b082357f31945bafc90b11dbdd680def479cf9 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -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); diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 5634775f99bbefbcd5107ec8b38f879df7a4552e..1b814f7bae502877eed59bb70b1f2d62cb68f9eb 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -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 */ diff --git a/src/ui/SerialConfigurationWindow.cc b/src/ui/SerialConfigurationWindow.cc index f9121c98b869fc0dca7bbe515527309a5cb22b9a..a736a866d00d5f10a69ac03e14fed41c82a06f76 100644 --- a/src/ui/SerialConfigurationWindow.cc +++ b/src/ui/SerialConfigurationWindow.cc @@ -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); diff --git a/src/ui/designer/QGCCommandButton.cc b/src/ui/designer/QGCCommandButton.cc index 69989a013e395c8647381dd2e07bb487218cb16a..d4cebf61174de4150b8e1343587ac64b0d6a1931 100644 --- a/src/ui/designer/QGCCommandButton.cc +++ b/src/ui/designer/QGCCommandButton.cc @@ -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(); diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index 9b97b588e14f460c3f7bb2ed8e5a69bea3cf68e9..c1651e3b6ab2a3731083370e36e97d57323ccf47 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -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()); diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h index 8bf064b4cbf10bdc8e684829aa1a71883c95db44..94783c549cb5778e175459d7a6cd92769880e08a 100644 --- a/src/ui/designer/QGCParamSlider.h +++ b/src/ui/designer/QGCParamSlider.h @@ -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); diff --git a/src/ui/designer/QGCToolWidget.cc b/src/ui/designer/QGCToolWidget.cc index e94073785d0439bdc5c44d42584fcf77c7398f11..b83437b4b2e52fdfaf06b6319dcd8d2863b8c858 100644 --- a/src/ui/designer/QGCToolWidget.cc +++ b/src/ui/designer/QGCToolWidget.cc @@ -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 systems = UASManager::instance()->getUASList(); - foreach (UASInterface* uas, systems) { + foreach (UASInterface* uas, systems) + { UAS* newMav = dynamic_cast(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::createWidgetsFromSettings(QWidget* parent, QList 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::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(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); - 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* QGCToolWidget::instances() @@ -317,7 +340,8 @@ QList* 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(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(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); diff --git a/src/ui/designer/QGCToolWidget.h b/src/ui/designer/QGCToolWidget.h index ac3de309a6d8cd3da1a253e7200e45a3921d0928..8747689cc814272f48688d1e64f37551c1c68e20 100644 --- a/src/ui/designer/QGCToolWidget.h +++ b/src/ui/designer/QGCToolWidget.h @@ -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 dockWidgetArea; ///< Dock widget area desired by this widget QMap 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: diff --git a/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h b/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h index a23c551176cb8d0e1897ff405e46a26340b4d349..67a76593416876c51cfeb3b55395e038af14b246 100644 --- a/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h +++ b/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 0, 28, 22, 22, 21, 0, 36, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 20, 32, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 0, 28, 22, 22, 21, 0, 36, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 20, 32, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 197, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 0, 104, 244, 237, 222, 0, 158, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 160, 168, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 197, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 0, 104, 244, 237, 222, 0, 158, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 160, 168, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, {NULL}, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, {NULL}, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} #endif #include "../protocol.h" @@ -47,6 +47,8 @@ extern "C" { // MESSAGE DEFINITIONS #include "./mavlink_msg_sensor_offsets.h" #include "./mavlink_msg_set_mag_offsets.h" +#include "./mavlink_msg_meminfo.h" +#include "./mavlink_msg_ap_adc.h" #ifdef __cplusplus } diff --git a/thirdParty/mavlink/include/ardupilotmega/mavlink_msg_ap_adc.h b/thirdParty/mavlink/include/ardupilotmega/mavlink_msg_ap_adc.h new file mode 100644 index 0000000000000000000000000000000000000000..dbe7f19370c84b1b80c1e0a91acafee0224d9eda --- /dev/null +++ b/thirdParty/mavlink/include/ardupilotmega/mavlink_msg_ap_adc.h @@ -0,0 +1,254 @@ +// 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 +} diff --git a/thirdParty/mavlink/include/ardupilotmega/mavlink_msg_meminfo.h b/thirdParty/mavlink/include/ardupilotmega/mavlink_msg_meminfo.h new file mode 100644 index 0000000000000000000000000000000000000000..85b7d96fc8f69f0adb9b1b2e2b9169236bbd6738 --- /dev/null +++ b/thirdParty/mavlink/include/ardupilotmega/mavlink_msg_meminfo.h @@ -0,0 +1,166 @@ +// 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 +} diff --git a/thirdParty/mavlink/include/ardupilotmega/testsuite.h b/thirdParty/mavlink/include/ardupilotmega/testsuite.h index fb4ca0a30c20a28198d708fee811d7e1b73fae77..c7cdc402f71beba400b854f39e28d60215cbef0b 100644 --- a/thirdParty/mavlink/include/ardupilotmega/testsuite.h +++ b/thirdParty/mavlink/include/ardupilotmega/testsuite.h @@ -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; imsg_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++; diff --git a/thirdParty/mavlink/include/mavlink_types.h b/thirdParty/mavlink/include/mavlink_types.h index f51fd2e788d5a122c037ec9de197648d5ff1b1ee..03faf594fe4ae7dbc3a86e24e6bb1540d7ab54ff 100644 --- a/thirdParty/mavlink/include/mavlink_types.h +++ b/thirdParty/mavlink/include/mavlink_types.h @@ -1,6 +1,8 @@ #ifndef MAVLINK_TYPES_H_ #define MAVLINK_TYPES_H_ +#include + 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 diff --git a/thirdParty/mavlink/include/minimal/version.h b/thirdParty/mavlink/include/minimal/version.h index 340c25f28a7c11a8945c8c243f4d39f0afc8b3ba..92c2b42babe5d86929984623c4af15d40a3bb30d 100644 --- a/thirdParty/mavlink/include/minimal/version.h +++ b/thirdParty/mavlink/include/minimal/version.h @@ -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 diff --git a/thirdParty/mavlink/include/pixhawk/version.h b/thirdParty/mavlink/include/pixhawk/version.h index 01d12756a8ff3081bd46e8e5b26a7c2647f2f31c..895c6625d2bf3537685c1495846be1c191f6fac8 100644 --- a/thirdParty/mavlink/include/pixhawk/version.h +++ b/thirdParty/mavlink/include/pixhawk/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 diff --git a/thirdParty/mavlink/include/protocol.h b/thirdParty/mavlink/include/protocol.h index e6d003413a696344b05566af0f969cf0a55c1574..27c2396836e839638ef2d0a186442943346b28e3 100644 --- a/thirdParty/mavlink/include/protocol.h +++ b/thirdParty/mavlink/include/protocol.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); diff --git a/thirdParty/mavlink/include/slugs/version.h b/thirdParty/mavlink/include/slugs/version.h index b8339ca565a61501b9b06bec2781a40f93a91564..ed420360c5aba5f1ea15fdf0ddb31d9639ae9d1d 100644 --- a/thirdParty/mavlink/include/slugs/version.h +++ b/thirdParty/mavlink/include/slugs/version.h @@ -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 diff --git a/thirdParty/mavlink/include/test/mavlink.h b/thirdParty/mavlink/include/test/mavlink.h deleted file mode 100644 index e596b8fba4fd4c75d48bc26751ee1ef0e1f52bc3..0000000000000000000000000000000000000000 --- a/thirdParty/mavlink/include/test/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @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 diff --git a/thirdParty/mavlink/include/test/mavlink_msg_test_types.h b/thirdParty/mavlink/include/test/mavlink_msg_test_types.h deleted file mode 100644 index c34b7ee3981a60b2c265e0cbc51448be41996e98..0000000000000000000000000000000000000000 --- a/thirdParty/mavlink/include/test/mavlink_msg_test_types.h +++ /dev/null @@ -1,610 +0,0 @@ -// MESSAGE TEST_TYPES PACKING - -#define MAVLINK_MSG_ID_TEST_TYPES 0 - -typedef struct __mavlink_test_types_t -{ - uint64_t u64; ///< uint64_t - int64_t s64; ///< int64_t - double d; ///< double - uint64_t u64_array[3]; ///< uint64_t_array - int64_t s64_array[3]; ///< int64_t_array - double d_array[3]; ///< double_array - uint32_t u32; ///< uint32_t - int32_t s32; ///< int32_t - float f; ///< float - uint32_t u32_array[3]; ///< uint32_t_array - int32_t s32_array[3]; ///< int32_t_array - float f_array[3]; ///< float_array - uint16_t u16; ///< uint16_t - int16_t s16; ///< int16_t - uint16_t u16_array[3]; ///< uint16_t_array - int16_t s16_array[3]; ///< int16_t_array - char c; ///< char - char s[10]; ///< string - uint8_t u8; ///< uint8_t - int8_t s8; ///< int8_t - uint8_t u8_array[3]; ///< uint8_t_array - int8_t s8_array[3]; ///< int8_t_array -} mavlink_test_types_t; - -#define MAVLINK_MSG_ID_TEST_TYPES_LEN 179 -#define MAVLINK_MSG_ID_0_LEN 179 - -#define MAVLINK_MSG_TEST_TYPES_FIELD_U64_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_S64_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_D_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_U32_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_S32_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_F_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_U16_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_S16_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_S_LEN 10 -#define MAVLINK_MSG_TEST_TYPES_FIELD_U8_ARRAY_LEN 3 -#define MAVLINK_MSG_TEST_TYPES_FIELD_S8_ARRAY_LEN 3 - -#define MAVLINK_MESSAGE_INFO_TEST_TYPES { \ - "TEST_TYPES", \ - 22, \ - { { "u64", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_test_types_t, u64) }, \ - { "s64", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_test_types_t, s64) }, \ - { "d", NULL, MAVLINK_TYPE_DOUBLE, 0, 16, offsetof(mavlink_test_types_t, d) }, \ - { "u64_array", NULL, MAVLINK_TYPE_UINT64_T, 3, 24, offsetof(mavlink_test_types_t, u64_array) }, \ - { "s64_array", NULL, MAVLINK_TYPE_INT64_T, 3, 48, offsetof(mavlink_test_types_t, s64_array) }, \ - { "d_array", NULL, MAVLINK_TYPE_DOUBLE, 3, 72, offsetof(mavlink_test_types_t, d_array) }, \ - { "u32", "0x%08x", MAVLINK_TYPE_UINT32_T, 0, 96, offsetof(mavlink_test_types_t, u32) }, \ - { "s32", NULL, MAVLINK_TYPE_INT32_T, 0, 100, offsetof(mavlink_test_types_t, s32) }, \ - { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 104, offsetof(mavlink_test_types_t, f) }, \ - { "u32_array", NULL, MAVLINK_TYPE_UINT32_T, 3, 108, offsetof(mavlink_test_types_t, u32_array) }, \ - { "s32_array", NULL, MAVLINK_TYPE_INT32_T, 3, 120, offsetof(mavlink_test_types_t, s32_array) }, \ - { "f_array", NULL, MAVLINK_TYPE_FLOAT, 3, 132, offsetof(mavlink_test_types_t, f_array) }, \ - { "u16", NULL, MAVLINK_TYPE_UINT16_T, 0, 144, offsetof(mavlink_test_types_t, u16) }, \ - { "s16", NULL, MAVLINK_TYPE_INT16_T, 0, 146, offsetof(mavlink_test_types_t, s16) }, \ - { "u16_array", NULL, MAVLINK_TYPE_UINT16_T, 3, 148, offsetof(mavlink_test_types_t, u16_array) }, \ - { "s16_array", NULL, MAVLINK_TYPE_INT16_T, 3, 154, offsetof(mavlink_test_types_t, s16_array) }, \ - { "c", NULL, MAVLINK_TYPE_CHAR, 0, 160, offsetof(mavlink_test_types_t, c) }, \ - { "s", NULL, MAVLINK_TYPE_CHAR, 10, 161, offsetof(mavlink_test_types_t, s) }, \ - { "u8", NULL, MAVLINK_TYPE_UINT8_T, 0, 171, offsetof(mavlink_test_types_t, u8) }, \ - { "s8", NULL, MAVLINK_TYPE_INT8_T, 0, 172, offsetof(mavlink_test_types_t, s8) }, \ - { "u8_array", NULL, MAVLINK_TYPE_UINT8_T, 3, 173, offsetof(mavlink_test_types_t, u8_array) }, \ - { "s8_array", NULL, MAVLINK_TYPE_INT8_T, 3, 176, offsetof(mavlink_test_types_t, s8_array) }, \ - } \ -} - - -/** - * @brief Pack a test_types 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 c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_test_types_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_uint64_t(buf, 0, u64); - _mav_put_int64_t(buf, 8, s64); - _mav_put_double(buf, 16, d); - _mav_put_uint32_t(buf, 96, u32); - _mav_put_int32_t(buf, 100, s32); - _mav_put_float(buf, 104, f); - _mav_put_uint16_t(buf, 144, u16); - _mav_put_int16_t(buf, 146, s16); - _mav_put_char(buf, 160, c); - _mav_put_uint8_t(buf, 171, u8); - _mav_put_int8_t(buf, 172, s8); - _mav_put_uint64_t_array(buf, 24, u64_array, 3); - _mav_put_int64_t_array(buf, 48, s64_array, 3); - _mav_put_double_array(buf, 72, d_array, 3); - _mav_put_uint32_t_array(buf, 108, u32_array, 3); - _mav_put_int32_t_array(buf, 120, s32_array, 3); - _mav_put_float_array(buf, 132, f_array, 3); - _mav_put_uint16_t_array(buf, 148, u16_array, 3); - _mav_put_int16_t_array(buf, 154, s16_array, 3); - _mav_put_char_array(buf, 161, s, 10); - _mav_put_uint8_t_array(buf, 173, u8_array, 3); - _mav_put_int8_t_array(buf, 176, s8_array, 3); - memcpy(_MAV_PAYLOAD(msg), buf, 179); -#else - mavlink_test_types_t packet; - packet.u64 = u64; - packet.s64 = s64; - packet.d = d; - packet.u32 = u32; - packet.s32 = s32; - packet.f = f; - packet.u16 = u16; - packet.s16 = s16; - packet.c = c; - packet.u8 = u8; - packet.s8 = s8; - memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - memcpy(packet.d_array, d_array, sizeof(double)*3); - memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - memcpy(packet.f_array, f_array, sizeof(float)*3); - memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - memcpy(packet.s, s, sizeof(char)*10); - memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - memcpy(_MAV_PAYLOAD(msg), &packet, 179); -#endif - - msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; - return mavlink_finalize_message(msg, system_id, component_id, 179, 103); -} - -/** - * @brief Pack a test_types 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 c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_uint64_t(buf, 0, u64); - _mav_put_int64_t(buf, 8, s64); - _mav_put_double(buf, 16, d); - _mav_put_uint32_t(buf, 96, u32); - _mav_put_int32_t(buf, 100, s32); - _mav_put_float(buf, 104, f); - _mav_put_uint16_t(buf, 144, u16); - _mav_put_int16_t(buf, 146, s16); - _mav_put_char(buf, 160, c); - _mav_put_uint8_t(buf, 171, u8); - _mav_put_int8_t(buf, 172, s8); - _mav_put_uint64_t_array(buf, 24, u64_array, 3); - _mav_put_int64_t_array(buf, 48, s64_array, 3); - _mav_put_double_array(buf, 72, d_array, 3); - _mav_put_uint32_t_array(buf, 108, u32_array, 3); - _mav_put_int32_t_array(buf, 120, s32_array, 3); - _mav_put_float_array(buf, 132, f_array, 3); - _mav_put_uint16_t_array(buf, 148, u16_array, 3); - _mav_put_int16_t_array(buf, 154, s16_array, 3); - _mav_put_char_array(buf, 161, s, 10); - _mav_put_uint8_t_array(buf, 173, u8_array, 3); - _mav_put_int8_t_array(buf, 176, s8_array, 3); - memcpy(_MAV_PAYLOAD(msg), buf, 179); -#else - mavlink_test_types_t packet; - packet.u64 = u64; - packet.s64 = s64; - packet.d = d; - packet.u32 = u32; - packet.s32 = s32; - packet.f = f; - packet.u16 = u16; - packet.s16 = s16; - packet.c = c; - packet.u8 = u8; - packet.s8 = s8; - memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - memcpy(packet.d_array, d_array, sizeof(double)*3); - memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - memcpy(packet.f_array, f_array, sizeof(float)*3); - memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - memcpy(packet.s, s, sizeof(char)*10); - memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - memcpy(_MAV_PAYLOAD(msg), &packet, 179); -#endif - - msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179, 103); -} - -/** - * @brief Encode a test_types 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 test_types C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) -{ - return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); -} - -/** - * @brief Send a test_types message - * @param chan MAVLink channel to send the message - * - * @param c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_uint64_t(buf, 0, u64); - _mav_put_int64_t(buf, 8, s64); - _mav_put_double(buf, 16, d); - _mav_put_uint32_t(buf, 96, u32); - _mav_put_int32_t(buf, 100, s32); - _mav_put_float(buf, 104, f); - _mav_put_uint16_t(buf, 144, u16); - _mav_put_int16_t(buf, 146, s16); - _mav_put_char(buf, 160, c); - _mav_put_uint8_t(buf, 171, u8); - _mav_put_int8_t(buf, 172, s8); - _mav_put_uint64_t_array(buf, 24, u64_array, 3); - _mav_put_int64_t_array(buf, 48, s64_array, 3); - _mav_put_double_array(buf, 72, d_array, 3); - _mav_put_uint32_t_array(buf, 108, u32_array, 3); - _mav_put_int32_t_array(buf, 120, s32_array, 3); - _mav_put_float_array(buf, 132, f_array, 3); - _mav_put_uint16_t_array(buf, 148, u16_array, 3); - _mav_put_int16_t_array(buf, 154, s16_array, 3); - _mav_put_char_array(buf, 161, s, 10); - _mav_put_uint8_t_array(buf, 173, u8_array, 3); - _mav_put_int8_t_array(buf, 176, s8_array, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179, 103); -#else - mavlink_test_types_t packet; - packet.u64 = u64; - packet.s64 = s64; - packet.d = d; - packet.u32 = u32; - packet.s32 = s32; - packet.f = f; - packet.u16 = u16; - packet.s16 = s16; - packet.c = c; - packet.u8 = u8; - packet.s8 = s8; - memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - memcpy(packet.d_array, d_array, sizeof(double)*3); - memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - memcpy(packet.f_array, f_array, sizeof(float)*3); - memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - memcpy(packet.s, s, sizeof(char)*10); - memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179, 103); -#endif -} - -#endif - -// MESSAGE TEST_TYPES UNPACKING - - -/** - * @brief Get field c from test_types message - * - * @return char - */ -static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) -{ - return _MAV_RETURN_char(msg, 160); -} - -/** - * @brief Get field s from test_types message - * - * @return string - */ -static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) -{ - return _MAV_RETURN_char_array(msg, s, 10, 161); -} - -/** - * @brief Get field u8 from test_types message - * - * @return uint8_t - */ -static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 171); -} - -/** - * @brief Get field u16 from test_types message - * - * @return uint16_t - */ -static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 144); -} - -/** - * @brief Get field u32 from test_types message - * - * @return uint32_t - */ -static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 96); -} - -/** - * @brief Get field u64 from test_types message - * - * @return uint64_t - */ -static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field s8 from test_types message - * - * @return int8_t - */ -static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 172); -} - -/** - * @brief Get field s16 from test_types message - * - * @return int16_t - */ -static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 146); -} - -/** - * @brief Get field s32 from test_types message - * - * @return int32_t - */ -static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 100); -} - -/** - * @brief Get field s64 from test_types message - * - * @return int64_t - */ -static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 8); -} - -/** - * @brief Get field f from test_types message - * - * @return float - */ -static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 104); -} - -/** - * @brief Get field d from test_types message - * - * @return double - */ -static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) -{ - return _MAV_RETURN_double(msg, 16); -} - -/** - * @brief Get field u8_array from test_types message - * - * @return uint8_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) -{ - return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 173); -} - -/** - * @brief Get field u16_array from test_types message - * - * @return uint16_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) -{ - return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 148); -} - -/** - * @brief Get field u32_array from test_types message - * - * @return uint32_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) -{ - return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 108); -} - -/** - * @brief Get field u64_array from test_types message - * - * @return uint64_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) -{ - return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 24); -} - -/** - * @brief Get field s8_array from test_types message - * - * @return int8_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) -{ - return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 176); -} - -/** - * @brief Get field s16_array from test_types message - * - * @return int16_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) -{ - return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 154); -} - -/** - * @brief Get field s32_array from test_types message - * - * @return int32_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) -{ - return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 120); -} - -/** - * @brief Get field s64_array from test_types message - * - * @return int64_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) -{ - return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 48); -} - -/** - * @brief Get field f_array from test_types message - * - * @return float_array - */ -static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) -{ - return _MAV_RETURN_float_array(msg, f_array, 3, 132); -} - -/** - * @brief Get field d_array from test_types message - * - * @return double_array - */ -static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) -{ - return _MAV_RETURN_double_array(msg, d_array, 3, 72); -} - -/** - * @brief Decode a test_types message into a struct - * - * @param msg The message to decode - * @param test_types C-struct to decode the message contents into - */ -static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) -{ -#if MAVLINK_NEED_BYTE_SWAP - test_types->u64 = mavlink_msg_test_types_get_u64(msg); - test_types->s64 = mavlink_msg_test_types_get_s64(msg); - test_types->d = mavlink_msg_test_types_get_d(msg); - mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); - mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); - mavlink_msg_test_types_get_d_array(msg, test_types->d_array); - test_types->u32 = mavlink_msg_test_types_get_u32(msg); - test_types->s32 = mavlink_msg_test_types_get_s32(msg); - test_types->f = mavlink_msg_test_types_get_f(msg); - mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); - mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); - mavlink_msg_test_types_get_f_array(msg, test_types->f_array); - test_types->u16 = mavlink_msg_test_types_get_u16(msg); - test_types->s16 = mavlink_msg_test_types_get_s16(msg); - mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); - mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); - test_types->c = mavlink_msg_test_types_get_c(msg); - mavlink_msg_test_types_get_s(msg, test_types->s); - test_types->u8 = mavlink_msg_test_types_get_u8(msg); - test_types->s8 = mavlink_msg_test_types_get_s8(msg); - mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); - mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); -#else - memcpy(test_types, _MAV_PAYLOAD(msg), 179); -#endif -} diff --git a/thirdParty/mavlink/include/test/test.h b/thirdParty/mavlink/include/test/test.h deleted file mode 100644 index 4dc04f889f5809f780b4eb3f55834ed832ed504c..0000000000000000000000000000000000000000 --- a/thirdParty/mavlink/include/test/test.h +++ /dev/null @@ -1,53 +0,0 @@ -/** @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 diff --git a/thirdParty/mavlink/include/test/testsuite.h b/thirdParty/mavlink/include/test/testsuite.h deleted file mode 100644 index bfb269fb5fb16a127001226a31d283e9088dfdca..0000000000000000000000000000000000000000 --- a/thirdParty/mavlink/include/test/testsuite.h +++ /dev/null @@ -1,120 +0,0 @@ -/** @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; iDescriptor Harris operator response at this location - + The system to be controlled roll pitch diff --git a/thirdParty/mavlink/message_definitions/test.xml b/thirdParty/mavlink/message_definitions/test.xml index 43a11e3d139782e3d7b008e898c6c7891828bd0e..02bc03204d11a3565e9a39ce4b2646e935a6bd2b 100644 --- a/thirdParty/mavlink/message_definitions/test.xml +++ b/thirdParty/mavlink/message_definitions/test.xml @@ -1,14 +1,14 @@ - 3 - + 3 + Test all field types - char - string + char + string uint8_t uint16_t - uint32_t + uint32_t uint64_t int8_t int16_t @@ -27,5 +27,5 @@ float_array double_array - + diff --git a/thirdParty/mavlink/missionlib/mavlink_parameters.c b/thirdParty/mavlink/missionlib/mavlink_parameters.c index 7e7937bfe3729b985ce6b3856e860168f5a29578..7ed8e7955d6576b41aee16af400d905a05d768a6 100644 --- a/thirdParty/mavlink/missionlib/mavlink_parameters.c +++ b/thirdParty/mavlink/missionlib/mavlink_parameters.c @@ -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); diff --git a/thirdParty/mavlink/missionlib/testing/main.c b/thirdParty/mavlink/missionlib/testing/main.c index eb75d4b7cd5b9eda93c4e8b10387b7411136639f..21aa1f7e15fae4367a5b0f8ab191f98d875e777f 100644 --- a/thirdParty/mavlink/missionlib/testing/main.c +++ b/thirdParty/mavlink/missionlib/testing/main.c @@ -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)); } diff --git a/thirdParty/mavlink/missionlib/waypoints.c b/thirdParty/mavlink/missionlib/waypoints.c index 17c70a2d060f69b375400bd8465bb147850858d1..79d7e29077770039bb8911038792ecab9f1bb75a 100644 --- a/thirdParty/mavlink/missionlib/waypoints.c +++ b/thirdParty/mavlink/missionlib/waypoints.c @@ -33,7 +33,7 @@ extern uint64_t mavlink_missionlib_get_system_timestamp(); #define MAVLINK_WPM_NO_PRINTF -uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_WAYPOINTPLANNER; +uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER; void mavlink_wpm_init(mavlink_wpm_storage* state) { @@ -64,13 +64,13 @@ void mavlink_wpm_init(mavlink_wpm_storage* state) void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type) { mavlink_message_t msg; - mavlink_waypoint_ack_t wpa; + mavlink_mission_ack_t wpa; wpa.target_system = wpm.current_partner_sysid; wpa.target_component = wpm.current_partner_compid; wpa.type = type; - mavlink_msg_waypoint_ack_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpa); + mavlink_msg_mission_ack_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpa); mavlink_missionlib_send_message(&msg); // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); @@ -99,14 +99,14 @@ void mavlink_wpm_send_waypoint_current(uint16_t seq) { if(seq < wpm.size) { - mavlink_waypoint_t *cur = &(wpm.waypoints[seq]); + mavlink_mission_item_t *cur = &(wpm.waypoints[seq]); mavlink_message_t msg; - mavlink_waypoint_current_t wpc; + mavlink_mission_current_t wpc; wpc.seq = cur->seq; - mavlink_msg_waypoint_current_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc); + mavlink_msg_mission_current_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc); mavlink_missionlib_send_message(&msg); // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); @@ -129,51 +129,51 @@ void mavlink_wpm_send_waypoint_current(uint16_t seq) */ void mavlink_wpm_send_setpoint(uint16_t seq) { - if(seq < wpm.size) - { - mavlink_waypoint_t *cur = &(wpm.waypoints[seq]); - - mavlink_message_t msg; - mavlink_local_position_setpoint_set_t position_control_set_point; - - // Send new NED or ENU setpoint to onbaord autopilot - if (cur->frame == MAV_FRAME_LOCAL_NED || cur->frame == MAV_FRAME_LOCAL_ENU) - { - position_control_set_point.target_system = mavlink_system.sysid; - position_control_set_point.target_component = MAV_COMP_ID_IMU; - position_control_set_point.x = cur->x; - position_control_set_point.y = cur->y; - position_control_set_point.z = cur->z; - position_control_set_point.yaw = cur->param4; - - mavlink_msg_local_position_setpoint_set_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &position_control_set_point); - mavlink_missionlib_send_message(&msg); - - // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); - } - else - { - if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("No new setpoint set because of invalid coordinate frame of waypoint");//// if (verbose) // printf("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq); - } - - wpm.timestamp_last_send_setpoint = mavlink_missionlib_get_system_timestamp(); - } - else - { - if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n"); //// if (verbose) // printf("ERROR: index out of bounds\n"); - } +// if(seq < wpm.size) +// { +// mavlink_mission_item_t *cur = &(wpm.waypoints[seq]); +// +// mavlink_message_t msg; +// mavlink_local_position_setpoint_set_t position_control_set_point; +// +// // Send new NED or ENU setpoint to onbaord autopilot +// if (cur->frame == MAV_FRAME_LOCAL_NED || cur->frame == MAV_FRAME_LOCAL_ENU) +// { +// position_control_set_point.target_system = mavlink_system.sysid; +// position_control_set_point.target_component = MAV_COMP_ID_IMU; +// position_control_set_point.x = cur->x; +// position_control_set_point.y = cur->y; +// position_control_set_point.z = cur->z; +// position_control_set_point.yaw = cur->param4; +// +// mavlink_msg_local_position_setpoint_set_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &position_control_set_point); +// mavlink_missionlib_send_message(&msg); +// +// // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY")); +// } +// else +// { +// if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("No new setpoint set because of invalid coordinate frame of waypoint");//// if (verbose) // printf("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq); +// } +// +// wpm.timestamp_last_send_setpoint = mavlink_missionlib_get_system_timestamp(); +// } +// else +// { +// if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n"); //// if (verbose) // printf("ERROR: index out of bounds\n"); +// } } void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count) { mavlink_message_t msg; - mavlink_waypoint_count_t wpc; + mavlink_mission_count_t wpc; wpc.target_system = wpm.current_partner_sysid; wpc.target_component = wpm.current_partner_compid; wpc.count = count; - mavlink_msg_waypoint_count_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc); + mavlink_msg_mission_count_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc); mavlink_missionlib_send_message(&msg); if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint count"); //// if (verbose) // printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system); @@ -186,10 +186,10 @@ void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq) if (seq < wpm.size) { mavlink_message_t msg; - mavlink_waypoint_t *wp = &(wpm.waypoints[seq]); + mavlink_mission_item_t *wp = &(wpm.waypoints[seq]); wp->target_system = wpm.current_partner_sysid; wp->target_component = wpm.current_partner_compid; - mavlink_msg_waypoint_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, wp); + mavlink_msg_mission_item_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, wp); mavlink_missionlib_send_message(&msg); if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint"); //// if (verbose) // printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system); @@ -206,11 +206,11 @@ void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t s if (seq < wpm.max_size) { mavlink_message_t msg; - mavlink_waypoint_request_t wpr; + mavlink_mission_request_t wpr; wpr.target_system = wpm.current_partner_sysid; wpr.target_component = wpm.current_partner_compid; wpr.seq = seq; - mavlink_msg_waypoint_request_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpr); + mavlink_msg_mission_request_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpr); mavlink_missionlib_send_message(&msg); if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint request"); //// if (verbose) // printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system); @@ -232,11 +232,11 @@ void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t s void mavlink_wpm_send_waypoint_reached(uint16_t seq) { mavlink_message_t msg; - mavlink_waypoint_reached_t wp_reached; + mavlink_mission_item_reached_t wp_reached; wp_reached.seq = seq; - mavlink_msg_waypoint_reached_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wp_reached); + mavlink_msg_mission_item_reached_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wp_reached); mavlink_missionlib_send_message(&msg); if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint reached message"); //// if (verbose) // printf("Sent waypoint %u reached message\n", wp_reached.seq); @@ -248,7 +248,7 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq) //{ // if (seq < wpm.size) // { -// mavlink_waypoint_t *cur = waypoints->at(seq); +// mavlink_mission_item_t *cur = waypoints->at(seq); // // const PxVector3 A(cur->x, cur->y, cur->z); // const PxVector3 C(x, y, z); @@ -256,7 +256,7 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq) // // seq not the second last waypoint // if ((uint16_t)(seq+1) < wpm.size) // { -// mavlink_waypoint_t *next = waypoints->at(seq+1); +// mavlink_mission_item_t *next = waypoints->at(seq+1); // const PxVector3 B(next->x, next->y, next->z); // const float r = (B-A).dot(C-A) / (B-A).lengthSquared(); // if (r >= 0 && r <= 1) @@ -289,7 +289,7 @@ float mavlink_wpm_distance_to_point(uint16_t seq, float x, float y, float z) { // if (seq < wpm.size) // { -// mavlink_waypoint_t *cur = waypoints->at(seq); +// mavlink_mission_item_t *cur = waypoints->at(seq); // // const PxVector3 A(cur->x, cur->y, cur->z); // const PxVector3 C(x, y, z); @@ -341,7 +341,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) { if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size) { - mavlink_waypoint_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); + mavlink_mission_item_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); if(wp->frame == MAV_FRAME_LOCAL_ENU || wp->frame == MAV_FRAME_LOCAL_NED) { mavlink_attitude_t att; @@ -370,16 +370,16 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) break; } - case MAVLINK_MSG_ID_LOCAL_POSITION: + case MAVLINK_MSG_ID_LOCAL_POSITION_NED: { if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size) { - mavlink_waypoint_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); + mavlink_mission_item_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]); if(wp->frame == MAV_FRAME_LOCAL_ENU || MAV_FRAME_LOCAL_NED) { - mavlink_local_position_t pos; - mavlink_msg_local_position_decode(msg, &pos); + mavlink_local_position_ned_t pos; + mavlink_msg_local_position_ned_decode(msg, &pos); //// if (debug) // printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z); wpm.pos_reached = false; @@ -447,10 +447,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) // break; // } - case MAVLINK_MSG_ID_WAYPOINT_ACK: + case MAVLINK_MSG_ID_MISSION_ACK: { - mavlink_waypoint_ack_t wpa; - mavlink_msg_waypoint_ack_decode(msg, &wpa); + mavlink_mission_ack_t wpa; + mavlink_msg_mission_ack_decode(msg, &wpa); if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/)) { @@ -481,10 +481,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) break; } - case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: + case MAVLINK_MSG_ID_MISSION_SET_CURRENT: { - mavlink_waypoint_set_current_t wpc; - mavlink_msg_waypoint_set_current_decode(msg, &wpc); + mavlink_mission_set_current_t wpc; + mavlink_msg_mission_set_current_decode(msg, &wpc); if(wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) { @@ -494,7 +494,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) { if (wpc.seq < wpm.size) { - // if (verbose) // printf("Received MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT\n"); + // if (verbose) // printf("Received MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT\n"); wpm.current_active_wp_id = wpc.seq; uint32_t i; for(i = 0; i < wpm.size; i++) @@ -524,7 +524,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: Index out of bounds\n"); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT: Index out of bounds\n"); #endif } } @@ -548,10 +548,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) break; } - case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: + case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: { - mavlink_waypoint_request_list_t wprl; - mavlink_msg_waypoint_request_list_decode(msg, &wprl); + mavlink_mission_request_list_t wprl; + mavlink_msg_mission_request_list_decode(msg, &wprl); if(wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) { wpm.timestamp_lastaction = now; @@ -560,8 +560,8 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) { if (wpm.size > 0) { - //if (verbose && wpm.current_state == MAVLINK_WPM_STATE_IDLE) // printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); -// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) // printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); + //if (verbose && wpm.current_state == MAVLINK_WPM_STATE_IDLE) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid); wpm.current_state = MAVLINK_WPM_STATE_SENDLIST; wpm.current_wp_id = 0; wpm.current_partner_sysid = msg->sysid; @@ -569,14 +569,14 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) } else { - // if (verbose) // printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid); + // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid); } wpm.current_count = wpm.size; mavlink_wpm_send_waypoint_count(msg->sysid,msg->compid, wpm.current_count); } else { - // if (verbose) // printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST because i'm doing something else already (state=%i).\n", wpm.current_state); + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).\n", wpm.current_state); } } else @@ -587,10 +587,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) break; } - case MAVLINK_MSG_ID_WAYPOINT_REQUEST: + case MAVLINK_MSG_ID_MISSION_REQUEST: { - mavlink_waypoint_request_t wpr; - mavlink_msg_waypoint_request_decode(msg, &wpr); + mavlink_mission_request_t wpr; + mavlink_msg_mission_request_decode(msg, &wpr); if(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid && wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) { wpm.timestamp_lastaction = now; @@ -603,7 +603,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("GOT WP REQ, state -> SEND"); #else - if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); #endif } if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id + 1) @@ -611,7 +611,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ"); #else - if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); #endif } if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id) @@ -619,7 +619,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ"); #else - if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid); #endif } @@ -636,7 +636,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because i'm doing something else already (state=%i).\n", wpm.current_state); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).\n", wpm.current_state); #endif break; } @@ -647,7 +647,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq); #endif } } @@ -658,7 +658,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, wpm.current_wp_id, wpm.current_wp_id+1); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, wpm.current_wp_id, wpm.current_wp_id+1); #endif } else if (wpr.seq >= wpm.size) @@ -666,7 +666,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq); #endif } } @@ -675,7 +675,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST - FIXME: missed error description\n"); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST - FIXME: missed error description\n"); #endif } } @@ -689,7 +689,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, wpm.current_partner_sysid); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, wpm.current_partner_sysid); #endif } else @@ -705,10 +705,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) break; } - case MAVLINK_MSG_ID_WAYPOINT_COUNT: + case MAVLINK_MSG_ID_MISSION_COUNT: { - mavlink_waypoint_count_t wpc; - mavlink_msg_waypoint_count_decode(msg, &wpc); + mavlink_mission_count_t wpc; + mavlink_msg_mission_count_decode(msg, &wpc); if(wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) { wpm.timestamp_lastaction = now; @@ -722,7 +722,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("WP CMD OK: state -> GETLIST"); #else - if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_WAYPOINT_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST\n", wpc.count, msg->sysid); + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST\n", wpc.count, msg->sysid); #endif } if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST) @@ -730,7 +730,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN"); #else - if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_WAYPOINT_COUNT (%u) again from %u\n", wpc.count, msg->sysid); + if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u\n", wpc.count, msg->sysid); #endif } @@ -778,7 +778,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("IGN WP CMD"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignoring MAVLINK_MSG_ID_WAYPOINT_COUNT from %u with count of %u\n", msg->sysid, wpc.count); + if (MAVLINK_WPM_VERBOSE) printf("Ignoring MAVLINK_MSG_ID_MISSION_ITEM_COUNT from %u with count of %u\n", msg->sysid, wpc.count); #endif } } @@ -789,7 +789,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT because i'm doing something else already (state=%i).\n", wpm.current_state); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm doing something else already (state=%i).\n", wpm.current_state); #endif } else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id != 0) @@ -797,7 +797,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT because i'm already receiving waypoint %u.\n", wpm.current_wp_id); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.\n", wpm.current_wp_id); #endif } else @@ -805,7 +805,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) #ifdef MAVLINK_WPM_NO_PRINTF mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?"); #else - if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_WAYPOINT_COUNT - FIXME: missed error description\n"); + if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT - FIXME: missed error description\n"); #endif } } @@ -822,10 +822,10 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) } break; - case MAVLINK_MSG_ID_WAYPOINT: + case MAVLINK_MSG_ID_MISSION_ITEM: { - mavlink_waypoint_t wp; - mavlink_msg_waypoint_decode(msg, &wp); + mavlink_mission_item_t wp; + mavlink_msg_mission_item_decode(msg, &wp); mavlink_missionlib_send_gcs_string("GOT WP"); @@ -836,13 +836,13 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) //ensure that we are in the correct state and that the first waypoint has id 0 and the following waypoints have the correct ids if ((wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wp.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id && wp.seq < wpm.current_count)) { -// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST) // printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid); -// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u\n", wp.seq, msg->sysid); -// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq-1 == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_WAYPOINT %u (again) from %u\n", wp.seq, msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u\n", wp.seq, msg->sysid); +// if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq-1 == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u (again) from %u\n", wp.seq, msg->sysid); // wpm.current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS; - mavlink_waypoint_t* newwp = &(wpm.rcv_waypoints[wp.seq]); - memcpy(newwp, &wp, sizeof(mavlink_waypoint_t)); + mavlink_mission_item_t* newwp = &(wpm.rcv_waypoints[wp.seq]); + memcpy(newwp, &wp, sizeof(mavlink_mission_item_t)); wpm.current_wp_id = wp.seq + 1; // if (verbose) // printf ("Added new waypoint to list. X= %f\t Y= %f\t Z= %f\t Yaw= %f\n", newwp->x, newwp->y, newwp->z, newwp->param4); @@ -905,44 +905,44 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) { //we're done receiving waypoints, answer with ack. mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0); - // printf("Received MAVLINK_MSG_ID_WAYPOINT while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n"); + // printf("Received MAVLINK_MSG_ID_MISSION_ITEM while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n"); } // if (verbose) { if (!(wpm.current_state == MAVLINK_WPM_STATE_GETLIST || wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)) { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u because i'm doing something else already (state=%i).\n", wp.seq, wpm.current_state); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u because i'm doing something else already (state=%i).\n", wp.seq, wpm.current_state); break; } else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST) { if(!(wp.seq == 0)) { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the first waypoint ID (%u) was not 0.\n", wp.seq); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.\n", wp.seq); } else { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq); } } else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { if (!(wp.seq == wpm.current_wp_id)) { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm.current_wp_id); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm.current_wp_id); } else if (!(wp.seq < wpm.current_count)) { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT because the waypoint ID (%u) was out of bounds.\n", wp.seq); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.\n", wp.seq); } else { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq); } } else { - // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u - FIXME: missed error description\n", wp.seq); + // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq); } } } @@ -952,26 +952,26 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) //we we're target but already communicating with someone else if((wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && wpm.current_state != MAVLINK_WPM_STATE_IDLE) { - // if (verbose) // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm.current_partner_sysid); + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm.current_partner_sysid); } else if(wp.target_system == mavlink_system.sysid /* && wp.target_component == mavlink_wpm_comp_id*/) { - // if (verbose) // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid); + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid); } } break; } - case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: + case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: { - mavlink_waypoint_clear_all_t wpca; - mavlink_msg_waypoint_clear_all_decode(msg, &wpca); + mavlink_mission_clear_all_t wpca; + mavlink_msg_mission_clear_all_decode(msg, &wpca); if(wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm.current_state == MAVLINK_WPM_STATE_IDLE) { wpm.timestamp_lastaction = now; - // if (verbose) // printf("Got MAVLINK_MSG_ID_WAYPOINT_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid); + // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid); // Delete all waypoints wpm.size = 0; wpm.current_active_wp_id = -1; @@ -980,7 +980,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) } else if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm.current_state != MAVLINK_WPM_STATE_IDLE) { - // if (verbose) // printf("Ignored MAVLINK_MSG_ID_WAYPOINT_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, wpm.current_state); + // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, wpm.current_state); } break; } @@ -997,7 +997,7 @@ void mavlink_wpm_message_handler(const mavlink_message_t* msg) { if (wpm.current_active_wp_id < wpm.size) { - mavlink_waypoint_t *cur_wp = &(wpm.waypoints[wpm.current_active_wp_id]); + mavlink_mission_item_t *cur_wp = &(wpm.waypoints[wpm.current_active_wp_id]); if (wpm.timestamp_firstinside_orbit == 0) { diff --git a/thirdParty/mavlink/missionlib/waypoints.h b/thirdParty/mavlink/missionlib/waypoints.h index 41e15043a270f0adcfe1e54c64bc6da2640c18c1..dd3f0e02b5262c4dbb46d1c92aca6d9c1f5c4e13 100644 --- a/thirdParty/mavlink/missionlib/waypoints.h +++ b/thirdParty/mavlink/missionlib/waypoints.h @@ -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;