mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-29 14:52:12 +01:00
Merge branch 'rel-14.01' of git://git.openpilot.org/OpenPilot into rel-14.01
This commit is contained in:
commit
8cb8977a9e
@ -2285,7 +2285,7 @@
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945280</color>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
@ -2297,37 +2297,17 @@
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler0</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve10>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Guidance</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Watchdog</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
<plotCurve2>
|
||||
<color>4294945280</color>
|
||||
<color>4278190335</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler1</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2335,9 +2315,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294945280</color>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2345,9 +2325,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294945280</color>
|
||||
<color>4278255615</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2355,9 +2335,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4294945280</color>
|
||||
<color>4294923775</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-GPS</uavField>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2365,9 +2345,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294945280</color>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavField>StackRemaining-Sensors</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2385,9 +2365,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4294945280</color>
|
||||
<color>4283760767</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-AHRSComms</uavField>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2395,15 +2375,35 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294945280</color>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<plotCurve10>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4283782527</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-RadioRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
<plotCurveCount>12</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
|
@ -60,8 +60,7 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow) :
|
||||
// put everything together
|
||||
QHBoxLayout *layout = new QHBoxLayout;
|
||||
layout->setSpacing(6);
|
||||
// cheat a bit with the margin to "nicely" center things vertically
|
||||
layout->setContentsMargins(6, 0, 4, 2);
|
||||
layout->setContentsMargins(5, 2, 5, 2);
|
||||
setLayout(layout);
|
||||
|
||||
layout->addWidget(new QLabel(tr("Connections:")), 0, Qt::AlignVCenter);
|
||||
|
@ -51,18 +51,23 @@
|
||||
class FieldTreeItem : public TreeItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
|
||||
FieldTreeItem(int index, const QList<QVariant> &data, TreeItem *parent = 0) :
|
||||
TreeItem(data, parent), m_index(index) {}
|
||||
|
||||
FieldTreeItem(int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
TreeItem(data, parent), m_index(index) {}
|
||||
|
||||
bool isEditable()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
virtual QWidget *createEditor(QWidget *parent) = 0;
|
||||
virtual QVariant getEditorValue(QWidget *editor) = 0;
|
||||
virtual void setEditorValue(QWidget *editor, QVariant value) = 0;
|
||||
virtual void apply() {}
|
||||
|
||||
protected:
|
||||
int m_index;
|
||||
};
|
||||
@ -70,12 +75,12 @@ protected:
|
||||
class EnumFieldTreeItem : public FieldTreeItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data,
|
||||
TreeItem *parent = 0) :
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_enumOptions(field->getOptions()), m_field(field) {}
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QVariant &data,
|
||||
TreeItem *parent = 0) :
|
||||
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_enumOptions(field->getOptions()), m_field(field) {}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
QStringList options = m_field->getOptions();
|
||||
@ -85,6 +90,7 @@ public:
|
||||
setChanged(tmpValIndex != value);
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
QString enumOptions(int index)
|
||||
{
|
||||
if ((index < 0) || (index >= m_enumOptions.length())) {
|
||||
@ -92,14 +98,16 @@ public:
|
||||
}
|
||||
return m_enumOptions.at(index);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
int value = data(dataColumn).toInt();
|
||||
int value = data().toInt();
|
||||
QStringList options = m_field->getOptions();
|
||||
|
||||
m_field->setValue(options[value], m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
QStringList options = m_field->getOptions();
|
||||
@ -111,14 +119,16 @@ public:
|
||||
setHighlight(true);
|
||||
}
|
||||
}
|
||||
|
||||
QWidget *createEditor(QWidget *parent)
|
||||
{
|
||||
QComboBox *editor = new QComboBox(parent);
|
||||
|
||||
// Setting ClickFocus lets the ComboBox stay open on Mac OSX.
|
||||
editor->setFocusPolicy(Qt::ClickFocus);
|
||||
foreach(QString option, m_enumOptions)
|
||||
editor->addItem(option);
|
||||
foreach(QString option, m_enumOptions) {
|
||||
editor->addItem(option);
|
||||
}
|
||||
return editor;
|
||||
}
|
||||
|
||||
@ -135,6 +145,7 @@ public:
|
||||
|
||||
comboBox->setCurrentIndex(value.toInt());
|
||||
}
|
||||
|
||||
private:
|
||||
QStringList m_enumOptions;
|
||||
UAVObjectField *m_field;
|
||||
@ -148,6 +159,7 @@ public:
|
||||
{
|
||||
setMinMaxValues();
|
||||
}
|
||||
|
||||
IntFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field)
|
||||
{
|
||||
@ -210,16 +222,19 @@ public:
|
||||
|
||||
spinBox->setValue(value.toInt());
|
||||
}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
setChanged(m_field->getValue(m_index) != value);
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
m_field->setValue(data(dataColumn).toInt(), m_index);
|
||||
m_field->setValue(data().toInt(), m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
int value = m_field->getValue(m_index).toInt();
|
||||
@ -241,18 +256,22 @@ class FloatFieldTreeItem : public FieldTreeItem {
|
||||
public:
|
||||
FloatFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, bool scientific = false, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific) {}
|
||||
|
||||
FloatFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, bool scientific = false, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific) {}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
setChanged(m_field->getValue(m_index) != value);
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
m_field->setValue(data(dataColumn).toDouble(), m_index);
|
||||
m_field->setValue(data().toDouble(), m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
double value = m_field->getValue(m_index).toDouble();
|
||||
@ -303,9 +322,115 @@ public:
|
||||
spinBox->setValue(value.toDouble());
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
UAVObjectField *m_field;
|
||||
bool m_useScientificNotation;
|
||||
};
|
||||
|
||||
class HexFieldTreeItem : public FieldTreeItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
HexFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field)
|
||||
{}
|
||||
|
||||
HexFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field)
|
||||
{}
|
||||
|
||||
QWidget *createEditor(QWidget *parent)
|
||||
{
|
||||
QLineEdit *lineEdit = new QLineEdit(parent);
|
||||
|
||||
lineEdit->setInputMask(QString(maxLength(), 'H'));
|
||||
|
||||
return lineEdit;
|
||||
}
|
||||
|
||||
QVariant getEditorValue(QWidget *editor)
|
||||
{
|
||||
QLineEdit *lineEdit = static_cast<QLineEdit *>(editor);
|
||||
|
||||
return lineEdit->text();
|
||||
}
|
||||
|
||||
void setEditorValue(QWidget *editor, QVariant value)
|
||||
{
|
||||
QLineEdit *lineEdit = static_cast<QLineEdit *>(editor);
|
||||
|
||||
lineEdit->setText(value.toString());
|
||||
}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
setChanged(m_field->getValue(m_index) != toUInt(value));
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
m_field->setValue(toUInt(data()), m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
QVariant value = toHexString(m_field->getValue(m_index));
|
||||
|
||||
if (data() != value || changed()) {
|
||||
TreeItem::setData(value);
|
||||
setHighlight(true);
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
UAVObjectField *m_field;
|
||||
|
||||
QVariant toHexString(QVariant value)
|
||||
{
|
||||
QString str;
|
||||
bool ok;
|
||||
|
||||
return str.setNum(value.toUInt(&ok), 16).toUpper();
|
||||
}
|
||||
|
||||
QVariant toUInt(QVariant str)
|
||||
{
|
||||
bool ok;
|
||||
|
||||
return str.toString().toUInt(&ok, 16);
|
||||
}
|
||||
|
||||
int maxLength()
|
||||
{
|
||||
int maxLength = 0;
|
||||
|
||||
switch (m_field->getType()) {
|
||||
case UAVObjectField::INT8:
|
||||
maxLength = 2;
|
||||
break;
|
||||
case UAVObjectField::INT16:
|
||||
maxLength = 4;
|
||||
break;
|
||||
case UAVObjectField::INT32:
|
||||
maxLength = 8;
|
||||
break;
|
||||
case UAVObjectField::UINT8:
|
||||
maxLength = 2;
|
||||
break;
|
||||
case UAVObjectField::UINT16:
|
||||
maxLength = 4;
|
||||
break;
|
||||
case UAVObjectField::UINT32:
|
||||
maxLength = 8;
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(false);
|
||||
break;
|
||||
}
|
||||
return maxLength;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // FIELDTREEITEM_H
|
||||
|
@ -228,7 +228,11 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt
|
||||
case UAVObjectField::UINT32:
|
||||
data.append(field->getValue(index));
|
||||
data.append(field->getUnits());
|
||||
item = new IntFieldTreeItem(field, index, data);
|
||||
if (field->getUnits().toLower() == "hex") {
|
||||
item = new HexFieldTreeItem(field, index, data);
|
||||
} else {
|
||||
item = new IntFieldTreeItem(field, index, data);
|
||||
}
|
||||
break;
|
||||
case UAVObjectField::FLOAT32:
|
||||
data.append(field->getValue(index));
|
||||
@ -351,9 +355,6 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
|
||||
return item->data(index.column());
|
||||
}
|
||||
|
||||
// if (role == Qt::DecorationRole)
|
||||
// return QIcon(":/core/images/openpilot_logo_128.png");
|
||||
|
||||
if (role == Qt::ToolTipRole) {
|
||||
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
|
||||
return item->description();
|
||||
|
@ -3,72 +3,70 @@
|
||||
<description>Task information</description>
|
||||
<field name="StackRemaining" units="bytes" type="uint16">
|
||||
<elementnames>
|
||||
<!-- system -->
|
||||
<elementname>System</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>AltitudeHold</elementname>
|
||||
<elementname>PathPlanner</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<elementname>OveroSync</elementname>
|
||||
<elementname>ModemRx</elementname>
|
||||
<elementname>ModemTx</elementname>
|
||||
<elementname>ModemStat</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
<elementname>EventDispatcher</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>CallbackScheduler0</elementname>
|
||||
<elementname>CallbackScheduler1</elementname>
|
||||
<elementname>CallbackScheduler2</elementname>
|
||||
<elementname>CallbackScheduler3</elementname>
|
||||
<!-- fligth -->
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<!-- navigation -->
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<!-- optional -->
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
</elementnames>
|
||||
</field>
|
||||
<field name="Running" units="bool" type="enum">
|
||||
<elementnames>
|
||||
<!-- system -->
|
||||
<elementname>System</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>AltitudeHold</elementname>
|
||||
<elementname>PathPlanner</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<elementname>OveroSync</elementname>
|
||||
<elementname>ModemRx</elementname>
|
||||
<elementname>ModemTx</elementname>
|
||||
<elementname>ModemStat</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
<elementname>EventDispatcher</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>CallbackScheduler0</elementname>
|
||||
<elementname>CallbackScheduler1</elementname>
|
||||
<elementname>CallbackScheduler2</elementname>
|
||||
<elementname>CallbackScheduler3</elementname>
|
||||
<!-- fligth -->
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<!-- navigation -->
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<!-- optional -->
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
</elementnames>
|
||||
<options>
|
||||
<option>False</option>
|
||||
@ -77,40 +75,39 @@
|
||||
</field>
|
||||
<field name="RunningTime" units="%" type="uint8">
|
||||
<elementnames>
|
||||
<!-- system -->
|
||||
<elementname>System</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>AltitudeHold</elementname>
|
||||
<elementname>PathPlanner</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<elementname>OveroSync</elementname>
|
||||
<elementname>ModemRx</elementname>
|
||||
<elementname>ModemTx</elementname>
|
||||
<elementname>ModemStat</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
<elementname>EventDispatcher</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>CallbackScheduler0</elementname>
|
||||
<elementname>CallbackScheduler1</elementname>
|
||||
<elementname>CallbackScheduler2</elementname>
|
||||
<elementname>CallbackScheduler3</elementname>
|
||||
<!-- fligth -->
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<!-- navigation -->
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<!-- optional -->
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
</elementnames>
|
||||
</field>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<access gcs="readonly" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="periodic" period="10000"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user