Commit 1b638340 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #2881 from DonLakeFlyer/Vibration

Add Vehicle.vibration property support, plus vibe page in instrument panel
parents 312317b8 69e5440c
......@@ -109,7 +109,9 @@
<file alias="QGroundControl/FlightMap/QGCSlider.qml">src/FlightMap/Widgets/QGCSlider.qml</file>
<file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/ValuesWidget.qml">src/FlightMap/Widgets/ValuesWidget.qml</file>
<file alias="QGroundControl/FlightMap/VibrationWidget.qml">src/FlightMap/Widgets/VibrationWidget.qml</file>
<file alias="QGroundControl/FlightMap/VehicleMapItem.qml">src/FlightMap/MapItems/VehicleMapItem.qml</file>
<file alias="QGroundControl/FlightMap/InstrumentSwipeView.qml">src/FlightMap/Widgets/InstrumentSwipeView.qml</file>
<file alias="QGroundControl/ScreenTools/qmldir">src/QmlControls/QGroundControl.ScreenTools.qmldir</file>
<file alias="QGroundControl/ScreenTools/ScreenTools.qml">src/QmlControls/ScreenTools.qml</file>
......@@ -158,5 +160,6 @@
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
</qresource>
</RCC>
......@@ -177,7 +177,7 @@ void FactGroup::_loadMetaData(const QString& jsonFilename)
// Make sure we have the required keys
QString errorString;
QStringList requiredKeys;
requiredKeys << _nameJsonKey << _decimalPlacesJsonKey << _typeJsonKey << _shortDescriptionJsonKey;
requiredKeys << _nameJsonKey << _typeJsonKey << _shortDescriptionJsonKey;
if (!JsonHelper::validateRequiredKeys(jsonObject, requiredKeys, errorString)) {
qWarning() << errorString;
return;
......@@ -215,7 +215,7 @@ void FactGroup::_loadMetaData(const QString& jsonFilename)
FactMetaData* metaData = new FactMetaData(type, this);
metaData->setDecimalPlaces(jsonObject.value(_decimalPlacesJsonKey).toInt());
metaData->setDecimalPlaces(jsonObject.value(_decimalPlacesJsonKey).toInt(0));
metaData->setShortDescription(jsonObject.value(_shortDescriptionJsonKey).toString());
metaData->setRawUnits(jsonObject.value(_unitsJsonKey).toString());
......
import QtQuick 2.5
import QtQuick.Controls 1.4
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.FlightMap 1.0
Item {
id: _root
clip: true
height: valuesPage.height + pageIndicatorRow.anchors.topMargin + pageIndicatorRow.height
property var qgcView ///< QGCView to use for showing dialogs
property color textColor
property color backgroundColor
property var maxHeight ///< Maximum height that should be taken, smaller than this is ok
property real _margins: ScreenTools.defaultFontPixelWidth / 2
ValuesWidget {
id: valuesPage
width: _root.width
qgcView: _root.qgcView
textColor: _root.textColor
maxHeight: _root.maxHeight
}
VibrationWidget {
id: vibrationPage
anchors.left: valuesPage.right
width: _root.width
textColor: _root.textColor
backgroundColor: _root.backgroundColor
maxHeight: _root.maxHeight
}
Row {
id: pageIndicatorRow
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
spacing: _margins
visible: multiVehicleManager.activeVehicle
Rectangle {
id: valuesPageIndicator
height: radius * 2
width: radius * 2
radius: 2.5
border.color: textColor
border.width: 1
color: textColor
}
Rectangle {
id: vibrationPageIndicator
height: radius * 2
width: radius * 2
radius: 2.5
border.color: textColor
border.width: 1
color: "transparent"
}
}
MouseArea {
anchors.fill: parent
property real xDragStart
property real xValuesPageSave
onPressed: {
if (mouse.button == Qt.LeftButton) {
mouse.accepted = true
xDragStart = mouse.x
xValuesPageSave = valuesPage.x
}
}
onPositionChanged: {
valuesPage.x = xValuesPageSave + mouse.x - xDragStart
}
onReleased: {
if (mouse.x < xDragStart) {
if (xValuesPageSave == 0) {
valuesPage.x = -valuesPage.width
_root.height = vibrationPage.height + pageIndicatorRow.anchors.topMargin + pageIndicatorRow.height
valuesPageIndicator.color = "transparent"
vibrationPageIndicator.color = textColor
} else {
valuesPage.x = xValuesPageSave
}
} else {
if (xValuesPageSave != 0) {
valuesPage.x = 0
_root.height = valuesPage.height + pageIndicatorRow.anchors.topMargin + pageIndicatorRow.height
valuesPageIndicator.color = textColor
vibrationPageIndicator.color = "transparent"
} else {
valuesPage.x = xValuesPageSave
}
}
}
}
}
......@@ -39,7 +39,7 @@ Rectangle {
height: compass.y + compass.height + _topBottomMargin
width: size
radius: size / 2
color: isSatellite ? Qt.rgba(1,1,1,0.75) : Qt.rgba(0,0,0,0.75)
color: _backgroundColor
property alias heading: compass.heading
property alias rollAngle: attitude.rollAngle
......@@ -56,12 +56,13 @@ Rectangle {
property real _defaultSize: ScreenTools.defaultFontPixelSize * (9)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
property real _bigFontSize: ScreenTools.defaultFontPixelSize * 2.5 * _sizeRatio
property real _normalFontSize:ScreenTools.defaultFontPixelSize * 1.5 * _sizeRatio
property real _labelFontSize: ScreenTools.defaultFontPixelSize * 0.75 * _sizeRatio
property real _spacing: ScreenTools.defaultFontPixelSize * 0.33
property real _topBottomMargin: (size * 0.05) / 2
property color _backgroundColor: isSatellite ? Qt.rgba(1,1,1,0.75) : Qt.rgba(0,0,0,0.75)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
property real _bigFontSize: ScreenTools.defaultFontPixelSize * 2.5 * _sizeRatio
property real _normalFontSize: ScreenTools.defaultFontPixelSize * 1.5 * _sizeRatio
property real _labelFontSize: ScreenTools.defaultFontPixelSize * 0.75 * _sizeRatio
property real _spacing: ScreenTools.defaultFontPixelSize * 0.33
property real _topBottomMargin: (size * 0.05) / 2
property real _availableValueHeight: maxHeight - (attitude.height + _spacer1.height + _spacer2.height + compass.height + (_spacing * 4))
MouseArea {
......@@ -105,16 +106,27 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter
}
ValuesWidget {
InstrumentSwipeView {
id: _valuesWidget
anchors.topMargin: _spacing
anchors.top: _spacer1.bottom
width: parent.width
qgcView: instrumentPanel.qgcView
textColor: isSatellite ? "black" : "white"
backgroundColor: _backgroundColor
maxHeight: _availableValueHeight
}
Component {
id: valuesPage
Rectangle {
width: 100
height: 100
color: index == 0 ? "red" : "blue"
}
}
Rectangle {
id: _spacer2
anchors.topMargin: _spacing
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
import QtQuick 2.4
import QtQuick.Controls 1.4
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.Palette 1.0
import QGroundControl 1.0
QGCFlickable {
id: _root
visible: _activeVehicle
height: Math.min(maxHeight, innerItem.height)
contentHeight: innerItem.height
flickableDirection: Flickable.VerticalFlick
clip: true
property color textColor
property color backgroundColor
property var maxHeight
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property real _margins: ScreenTools.defaultFontPixelWidth / 2
property real _barWidth: Math.round(ScreenTools.defaultFontPixelWidth * 3)
readonly property real _barMinimum: 0.0
readonly property real _barMaximum: 90.0
readonly property real _barBadValue: 60.0
QGCPalette { id:qgcPal; colorGroupEnabled: true }
Item {
id: innerItem
width: parent.width
height: barRow.y + barRow.height
QGCLabel {
id: title
color: textColor
text: "Vibe"
anchors.horizontalCenter: barRow.horizontalCenter
}
Row {
id: barRow
anchors.margins: _margins
anchors.top: title.bottom
anchors.left: parent.left
spacing: _margins
Column {
ProgressBar {
id: xBar
height: 50
orientation: Qt.Vertical
minimumValue: _barMinimum
maximumValue: _barMaximum
value: _activeVehicle ? _activeVehicle.vibration.xAxis.value : 0
}
QGCLabel {
id: xBarLabel
color: textColor
text: "X"
anchors.horizontalCenter: xBar.horizontalCenter
}
}
Column {
ProgressBar {
id: yBar
height: 50
orientation: Qt.Vertical
minimumValue: _barMinimum
maximumValue: _barMaximum
value: _activeVehicle ? _activeVehicle.vibration.yAxis.value : 0
}
QGCLabel {
anchors.horizontalCenter: yBar.horizontalCenter
color: textColor
text: "Y"
}
}
Column {
ProgressBar {
id: zBar
height: 50
orientation: Qt.Vertical
minimumValue: _barMinimum
maximumValue: _barMaximum
value: _activeVehicle ? _activeVehicle.vibration.zAxis.value : 0
}
QGCLabel {
anchors.horizontalCenter: zBar.horizontalCenter
color: textColor
text: "Z"
}
}
} // Row
// Max vibe indication line at 60
Rectangle {
anchors.topMargin: xBar.height * (1.0 - ((_barBadValue - _barMinimum) / (_barMaximum - _barMinimum)))
anchors.top: barRow.top
anchors.left: barRow.left
anchors.right: barRow.right
width: barRow.width
height: 1
color: "red"
Component.onCompleted: console.log(anchors.topMargin, xBar.height, _barBadValue, _barMaximum, _barMinimum)
}
QGCLabel {
id: clipLabel
anchors.margins: _margins
anchors.left: barRow.right
anchors.right: parent.right
color: textColor
text: "Clip count"
horizontalAlignment: Text.AlignHCenter
}
Column {
id: clipColumn
anchors.top: barRow.top
anchors.horizontalCenter: clipLabel.horizontalCenter
QGCLabel {
text: "Accel 1: " + (_activeVehicle ? _activeVehicle.vibration.clipCount1.valueString : "")
color: textColor
}
QGCLabel {
text: "Accel 2: " + (_activeVehicle ? _activeVehicle.vibration.clipCount2.valueString : "")
color: textColor
}
QGCLabel {
text: "Accel 2: " + (_activeVehicle ? _activeVehicle.vibration.clipCount3.valueString : "")
color: textColor
}
}
// Not available overlay
Rectangle {
anchors.fill: parent
color: backgroundColor
opacity: 0.95
visible: _activeVehicle ? isNaN(_activeVehicle.vibration.xAxis.value) : false
QGCLabel {
anchors.fill: parent
text: "Not Available"
color: textColor
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
}
}
} // Item
} // QGCFLickable
......@@ -5,6 +5,7 @@ FlightMap 1.0 FlightMap.qml
QGCVideoBackground 1.0 QGCVideoBackground.qml
# Widgets
InstrumentSwipeView 1.0 InstrumentSwipeView.qml
QGCArtificialHorizon 1.0 QGCArtificialHorizon.qml
QGCAttitudeHUD 1.0 QGCAttitudeHUD.qml
QGCAttitudeWidget 1.0 QGCAttitudeWidget.qml
......@@ -14,6 +15,7 @@ QGCInstrumentWidgetAlternate 1.0 QGCInstrumentWidgetAlternate.qml
QGCPitchIndicator 1.0 QGCPitchIndicator.qml
QGCSlider 1.0 QGCSlider.qml
ValuesWidget 1.0 ValuesWidget.qml
VibrationWidget 1.0 VibrationWidget.qml
# Map items
MissionItemIndicator 1.0 MissionItemIndicator.qml
......
......@@ -58,6 +58,7 @@ const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_batteryFactGroupName = "battery";
const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
......@@ -83,6 +84,13 @@ const char* VehicleWindFactGroup::_directionFactName = "direction";
const char* VehicleWindFactGroup::_speedFactName = "speed";
const char* VehicleWindFactGroup::_verticalSpeedFactName = "verticalSpeed";
const char* VehicleVibrationFactGroup::_xAxisFactName = "xAxis";
const char* VehicleVibrationFactGroup::_yAxisFactName = "yAxis";
const char* VehicleVibrationFactGroup::_zAxisFactName = "zAxis";
const char* VehicleVibrationFactGroup::_clipCount1FactName = "clipCount1";
const char* VehicleVibrationFactGroup::_clipCount2FactName = "clipCount2";
const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
MAV_AUTOPILOT firmwareType,
......@@ -150,6 +158,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _gpsFactGroup(this)
, _batteryFactGroup(this)
, _windFactGroup(this)
, _vibrationFactGroup(this)
{
_addLink(link);
......@@ -232,10 +241,12 @@ Vehicle::Vehicle(LinkInterface* link,
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_gpsFactGroup.setVehicle(this);
_batteryFactGroup.setVehicle(this);
_windFactGroup.setVehicle(this);
_vibrationFactGroup.setVehicle(this);
}
Vehicle::~Vehicle()
......@@ -333,6 +344,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_SCALED_IMU3:
emit mavlinkScaledImu3(message);
break;
case MAVLINK_MSG_ID_VIBRATION:
_handleVibration(message);
break;
// Following are ArduPilot dialect messages
......@@ -346,6 +360,19 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
_uas->receiveMessage(message);
}
void Vehicle::_handleVibration(mavlink_message_t& message)
{
mavlink_vibration_t vibration;
mavlink_msg_vibration_decode(&message, &vibration);
_vibrationFactGroup.xAxis()->setRawValue(vibration.vibration_x);
_vibrationFactGroup.yAxis()->setRawValue(vibration.vibration_y);
_vibrationFactGroup.zAxis()->setRawValue(vibration.vibration_z);
_vibrationFactGroup.clipCount1()->setRawValue(vibration.clipping_0);
_vibrationFactGroup.clipCount2()->setRawValue(vibration.clipping_1);
_vibrationFactGroup.clipCount3()->setRawValue(vibration.clipping_2);
}
void Vehicle::_handleWind(mavlink_message_t& message)
{
mavlink_wind_t wind;
......@@ -1357,3 +1384,31 @@ void VehicleWindFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent)
, _vehicle(NULL)
, _xAxisFact (0, _xAxisFactName, FactMetaData::valueTypeDouble)
, _yAxisFact (0, _yAxisFactName, FactMetaData::valueTypeDouble)
, _zAxisFact (0, _zAxisFactName, FactMetaData::valueTypeDouble)
, _clipCount1Fact (0, _clipCount1FactName, FactMetaData::valueTypeUint32)
, _clipCount2Fact (0, _clipCount2FactName, FactMetaData::valueTypeUint32)
, _clipCount3Fact (0, _clipCount3FactName, FactMetaData::valueTypeUint32)
{
_addFact(&_xAxisFact, _xAxisFactName);
_addFact(&_yAxisFact, _yAxisFactName);
_addFact(&_zAxisFact, _zAxisFactName);
_addFact(&_clipCount1Fact, _clipCount1FactName);
_addFact(&_clipCount2Fact, _clipCount2FactName);
_addFact(&_clipCount3Fact, _clipCount3FactName);
// Start out as not available "--.--"
_xAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
_zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
}
void VehicleVibrationFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
......@@ -52,6 +52,46 @@ Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
class Vehicle;
class VehicleVibrationFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleVibrationFactGroup(QObject* parent = NULL);
Q_PROPERTY(Fact* xAxis READ xAxis CONSTANT)
Q_PROPERTY(Fact* yAxis READ yAxis CONSTANT)
Q_PROPERTY(Fact* zAxis READ zAxis CONSTANT)
Q_PROPERTY(Fact* clipCount1 READ clipCount1 CONSTANT)
Q_PROPERTY(Fact* clipCount2 READ clipCount2 CONSTANT)
Q_PROPERTY(Fact* clipCount3 READ clipCount3 CONSTANT)
Fact* xAxis(void) { return &_xAxisFact; }
Fact* yAxis(void) { return &_yAxisFact; }
Fact* zAxis(void) { return &_zAxisFact; }
Fact* clipCount1(void) { return &_clipCount1Fact; }
Fact* clipCount2(void) { return &_clipCount2Fact; }
Fact* clipCount3(void) { return &_clipCount3Fact; }
void setVehicle(Vehicle* vehicle);
static const char* _xAxisFactName;
static const char* _yAxisFactName;
static const char* _zAxisFactName;
static const char* _clipCount1FactName;
static const char* _clipCount2FactName;
static const char* _clipCount3FactName;
private:
Vehicle* _vehicle;
Fact _xAxisFact;
Fact _yAxisFact;
Fact _zAxisFact;
Fact _clipCount1Fact;
Fact _clipCount2Fact;
Fact _clipCount3Fact;
};
class VehicleWindFactGroup : public FactGroup
{
Q_OBJECT
......@@ -73,8 +113,6 @@ public:
static const char* _speedFactName;
static const char* _verticalSpeedFactName;
private slots:
private:
Vehicle* _vehicle;
Fact _directionFact;
......@@ -242,7 +280,8 @@ public:
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery READ batteryFactGroup CONSTANT)
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
/// Resets link status counters
Q_INVOKABLE void resetCounters ();
......@@ -389,9 +428,10 @@ public:
Fact* altitudeRelative (void) { return &_altitudeRelativeFact; }
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* batteryFactGroup (void) { return &_batteryFactGroup; }
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* batteryFactGroup (void) { return &_batteryFactGroup; }
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
......@@ -495,6 +535,7 @@ private:
void _handleBatteryStatus(mavlink_message_t& message);
void _handleSysStatus(mavlink_message_t& message);
void _handleWind(mavlink_message_t& message);
void _handleVibration(mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg);
void _mapTrajectoryStart(void);
void _mapTrajectoryStop(void);
......@@ -605,9 +646,10 @@ private:
Fact _altitudeRelativeFact;
Fact _altitudeAMSLFact;
VehicleGPSFactGroup _gpsFactGroup;
VehicleBatteryFactGroup _batteryFactGroup;
VehicleWindFactGroup _windFactGroup;
VehicleGPSFactGroup _gpsFactGroup;
VehicleBatteryFactGroup _batteryFactGroup;
VehicleWindFactGroup _windFactGroup;
VehicleVibrationFactGroup _vibrationFactGroup;
static const char* _rollFactName;
static const char* _pitchFactName;
......@@ -621,6 +663,7 @@ private:
static const char* _gpsFactGroupName;
static const char* _batteryFactGroupName;
static const char* _windFactGroupName;
static const char* _vibrationFactGroupName;
static const int _vehicleUIUpdateRateMSecs = 100;
......
{
"version": 1,
"properties": [
{
"name": "xAxis",
"shortDescription": "Vibe xAxis",
"type": "double",
"decimalPlaces": 1
},
{
"name": "yAxis",
"shortDescription": "Vibe yAxis",
"type": "double",
"decimalPlaces": 1
},
{
"name": "zAxis",
"shortDescription": "Vibe zAxis",
"type": "double",
"decimalPlaces": 1
},
{
"name": "clipCount1",
"shortDescription": "Clip Count (1)",
"type": "uint32"
},
{
"name": "clipCount2",
"shortDescription": "Clip Count (2)",
"type": "uint32"
},
{
"name": "clipCount3",
"shortDescription": "Clip Count (3)",
"type": "uint32"
}
]
}
......@@ -174,6 +174,7 @@ void MockLink::_run1HzTasks(void)
{
if (_mavlinkStarted && _connected) {
_sendHeartBeat();
_sendVibration();
if (_sendHomePositionDelayCount > 0) {
// We delay home position a bit to be more realistic
_sendHomePositionDelayCount--;
......@@ -288,6 +289,24 @@ void MockLink::_sendHeartBeat(void)
respondWithMavlinkMessage(msg);
}
void MockLink::_sendVibration(void)
{
mavlink_message_t msg;
mavlink_msg_vibration_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
0, // time_usec
50.5, // vibration_x,
10.5, // vibration_y,
60.0, // vibration_z,
1, // clipping_0
2, // clipping_0
3); // clipping_0
respondWithMavlinkMessage(msg);
}
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
......
......@@ -192,6 +192,7 @@ private:
void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat);
void _sendHomePosition(void);
void _sendGpsRawInt(void);
void _sendVibration(void);
void _sendStatusTextMessages(void);
static MockLink* _startMockLink(MockConfiguration* mockConfig);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment