Commit c92caca1 authored by olliw42's avatar olliw42

Merge branch 'master' into pr-compid-2nd

parents 0ac171d9 0cb4bf8b
Subproject commit 68869da6575d4ca61b92e9081b7c81587f157ed6 Subproject commit cd003f27415dcb7abd94867fd5c44cda2fc3bdf5
...@@ -324,10 +324,26 @@ QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message) ...@@ -324,10 +324,26 @@ QGCMAVLinkVehicle::append(QGCMAVLinkMessage* message)
emit m->indexChanged(); emit m->indexChanged();
} }
} }
_checkCompID(message);
} }
emit messagesChanged(); emit messagesChanged();
} }
//-----------------------------------------------------------------------------
void
QGCMAVLinkVehicle::_checkCompID(QGCMAVLinkMessage* message)
{
if(_compIDsStr.isEmpty()) {
_compIDsStr << tr("All");
}
if(!_compIDs.contains(static_cast<int>(message->cid()))) {
int cid = static_cast<int>(message->cid());
_compIDs.append(cid);
_compIDsStr << QString::number(cid);
emit compIDsChanged();
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
MAVLinkInspectorController::MAVLinkInspectorController() MAVLinkInspectorController::MAVLinkInspectorController()
{ {
...@@ -430,9 +446,8 @@ MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle) ...@@ -430,9 +446,8 @@ MAVLinkInspectorController::_vehicleRemoved(Vehicle* vehicle)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
MAVLinkInspectorController::_receiveMessage(LinkInterface* link, mavlink_message_t message) MAVLinkInspectorController::_receiveMessage(LinkInterface*, mavlink_message_t message)
{ {
Q_UNUSED(link);
QGCMAVLinkMessage* m = nullptr; QGCMAVLinkMessage* m = nullptr;
QGCMAVLinkVehicle* v = _findVehicle(message.sysid); QGCMAVLinkVehicle* v = _findVehicle(message.sysid);
if(!v) { if(!v) {
...@@ -453,7 +468,6 @@ MAVLinkInspectorController::_receiveMessage(LinkInterface* link, mavlink_message ...@@ -453,7 +468,6 @@ MAVLinkInspectorController::_receiveMessage(LinkInterface* link, mavlink_message
} else { } else {
m->update(&message); m->update(&message);
} }
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -87,22 +87,32 @@ class QGCMAVLinkVehicle : public QObject { ...@@ -87,22 +87,32 @@ class QGCMAVLinkVehicle : public QObject {
Q_OBJECT Q_OBJECT
Q_PROPERTY(quint8 id READ id CONSTANT) Q_PROPERTY(quint8 id READ id CONSTANT)
Q_PROPERTY(QmlObjectListModel* messages READ messages NOTIFY messagesChanged) Q_PROPERTY(QmlObjectListModel* messages READ messages NOTIFY messagesChanged)
Q_PROPERTY(QList<int> compIDs READ compIDs NOTIFY compIDsChanged)
Q_PROPERTY(QStringList compIDsStr READ compIDsStr NOTIFY compIDsChanged)
public: public:
QGCMAVLinkVehicle(QObject* parent, quint8 id); QGCMAVLinkVehicle(QObject* parent, quint8 id);
quint8 id () { return _id; } quint8 id () { return _id; }
QmlObjectListModel* messages () { return &_messages; } QmlObjectListModel* messages () { return &_messages; }
QList<int> compIDs () { return _compIDs; }
QStringList compIDsStr () { return _compIDsStr; }
QGCMAVLinkMessage* findMessage (uint32_t id, uint8_t cid); QGCMAVLinkMessage* findMessage (uint32_t id, uint8_t cid);
void append (QGCMAVLinkMessage* message); void append (QGCMAVLinkMessage* message);
signals: signals:
void messagesChanged (); void messagesChanged ();
void compIDsChanged ();
private:
void _checkCompID (QGCMAVLinkMessage *message);
private: private:
quint8 _id; quint8 _id;
QmlObjectListModel _messages; //-- List of QGCMAVLinkMessage QList<int> _compIDs;
QStringList _compIDsStr;
QmlObjectListModel _messages; //-- List of QGCMAVLinkMessage
}; };
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -22,9 +22,11 @@ Item { ...@@ -22,9 +22,11 @@ Item {
anchors.fill: parent anchors.fill: parent
anchors.margins: ScreenTools.defaultFontPixelWidth anchors.margins: ScreenTools.defaultFontPixelWidth
property var curVehicle: controller ? controller.activeVehicle : null property var curVehicle: controller ? controller.activeVehicle : null
property int curMessageIndex: 0 property int curMessageIndex:0
property var curMessage: curVehicle && curVehicle.messages.count ? curVehicle.messages.get(curMessageIndex) : null property var curMessage: curVehicle && curVehicle.messages.count ? curVehicle.messages.get(curMessageIndex) : null
property int curCompID: 0
property bool selectionValid: false
MAVLinkInspectorController { MAVLinkInspectorController {
id: controller id: controller
...@@ -35,11 +37,36 @@ Item { ...@@ -35,11 +37,36 @@ Item {
} }
//-- Header //-- Header
QGCLabel { RowLayout {
id: header id: header
text: qsTr("Inspect real time MAVLink messages.")
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right
QGCLabel {
text: qsTr("Inspect real time MAVLink messages.")
}
RowLayout {
Layout.alignment: Qt.AlignRight
visible: curVehicle ? curVehicle.compIDsStr.length > 2 : false
QGCLabel {
text: qsTr("Component ID:")
}
QGCComboBox {
id: cidCombo
model: curVehicle ? curVehicle.compIDsStr : []
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 10
currentIndex: 0
onActivated: {
if(curVehicle && curVehicle.compIDsStr.length > 1) {
selectionValid = false
if(index < 1)
curCompID = 0
else
curCompID = curVehicle.compIDs[index - 1]
}
}
}
}
} }
//-- Messages (Buttons) //-- Messages (Buttons)
...@@ -59,10 +86,15 @@ Item { ...@@ -59,10 +86,15 @@ Item {
model: curVehicle ? curVehicle.messages : [] model: curVehicle ? curVehicle.messages : []
delegate: MAVLinkMessageButton { delegate: MAVLinkMessageButton {
text: object.name text: object.name
compID: object.cid
checked: curMessageIndex === index checked: curMessageIndex === index
messageHz: object.messageHz messageHz: object.messageHz
onClicked: curMessageIndex = index visible: curCompID === 0 || curCompID === compID
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36 onClicked: {
selectionValid = true
curMessageIndex = index
}
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 40
} }
} }
} }
...@@ -70,7 +102,7 @@ Item { ...@@ -70,7 +102,7 @@ Item {
//-- Message Data //-- Message Data
QGCFlickable { QGCFlickable {
id: messageGrid id: messageGrid
visible: curMessage !== null visible: curMessage !== null && selectionValid
anchors.top: buttonGrid.top anchors.top: buttonGrid.top
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
anchors.left: buttonGrid.right anchors.left: buttonGrid.right
......
...@@ -11,6 +11,8 @@ add_library(AutoPilotPlugins ...@@ -11,6 +11,8 @@ add_library(AutoPilotPlugins
APM/APMCompassCal.cc APM/APMCompassCal.cc
APM/APMFlightModesComponent.cc APM/APMFlightModesComponent.cc
APM/APMFlightModesComponentController.cc APM/APMFlightModesComponentController.cc
APM/APMFollowComponent.cc
APM/APMFollowComponentController.cc
APM/APMHeliComponent.cc APM/APMHeliComponent.cc
APM/APMLightsComponent.cc APM/APMLightsComponent.cc
APM/APMMotorComponent.cc APM/APMMotorComponent.cc
......
...@@ -52,7 +52,7 @@ SetupPage { ...@@ -52,7 +52,7 @@ SetupPage {
property Fact _rcLossAction: controller.getParameterFact(-1, "NAV_RCL_ACT") property Fact _rcLossAction: controller.getParameterFact(-1, "NAV_RCL_ACT")
property Fact _dlLossAction: controller.getParameterFact(-1, "NAV_DLL_ACT") property Fact _dlLossAction: controller.getParameterFact(-1, "NAV_DLL_ACT")
property Fact _disarmLandDelay: controller.getParameterFact(-1, "COM_DISARM_LAND") property Fact _disarmLandDelay: controller.getParameterFact(-1, "COM_DISARM_LAND")
property Fact _collisionPrevention: controller.getParameterFact(-1, "MPC_COL_PREV_D") property Fact _collisionPrevention: controller.getParameterFact(-1, "CP_DIST")
property Fact _objectAvoidance: controller.getParameterFact(-1, "COM_OBS_AVOID") property Fact _objectAvoidance: controller.getParameterFact(-1, "COM_OBS_AVOID")
property Fact _landSpeedMC: controller.getParameterFact(-1, "MPC_LAND_SPEED", false) property Fact _landSpeedMC: controller.getParameterFact(-1, "MPC_LAND_SPEED", false)
property bool _hitlAvailable: controller.parameterExists(-1, hitlParam) property bool _hitlAvailable: controller.parameterExists(-1, hitlParam)
......
...@@ -16,50 +16,58 @@ APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable) ...@@ -16,50 +16,58 @@ APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable) : APMCustomMode(mode, settable)
{ {
setEnumToStringMapping({ setEnumToStringMapping({
{MANUAL, "Manual"}, { MANUAL, "Manual" },
{CIRCLE, "Circle"}, { CIRCLE, "Circle" },
{STABILIZE, "Stabilize"}, { STABILIZE, "Stabilize" },
{TRAINING, "Training"}, { TRAINING, "Training" },
{ACRO, "Acro"}, { ACRO, "Acro" },
{FLY_BY_WIRE_A, "FBW A"}, { FLY_BY_WIRE_A, "FBW A" },
{FLY_BY_WIRE_B, "FBW B"}, { FLY_BY_WIRE_B, "FBW B" },
{CRUISE, "Cruise"}, { CRUISE, "Cruise" },
{AUTOTUNE, "Autotune"}, { AUTOTUNE, "Autotune" },
{AUTO, "Auto"}, { AUTO, "Auto" },
{RTL, "RTL"}, { RTL, "RTL" },
{LOITER, "Loiter"}, { LOITER, "Loiter" },
{GUIDED, "Guided"}, { TAKEOFF, "Takeoff" },
{INITIALIZING, "Initializing"}, { AVOID_ADSB, "Avoid ADSB" },
{QSTABILIZE, "QuadPlane Stabilize"}, { GUIDED, "Guided" },
{QHOVER, "QuadPlane Hover"}, { INITIALIZING, "Initializing" },
{QLOITER, "QuadPlane Loiter"}, { QSTABILIZE, "QuadPlane Stabilize" },
{QLAND, "QuadPlane Land"}, { QHOVER, "QuadPlane Hover" },
{QRTL, "QuadPlane RTL"}, { QLOITER, "QuadPlane Loiter" },
{ QLAND, "QuadPlane Land" },
{ QRTL, "QuadPlane RTL" },
{ QAUTOTUNE, "QuadPlane AutoTune" },
{ QACRO, "QuadPlane Acro" },
}); });
} }
ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void) ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
{ {
setSupportedModes({ setSupportedModes({
APMPlaneMode(APMPlaneMode::MANUAL ,true), APMPlaneMode(APMPlaneMode::MANUAL, true),
APMPlaneMode(APMPlaneMode::CIRCLE ,true), APMPlaneMode(APMPlaneMode::CIRCLE, true),
APMPlaneMode(APMPlaneMode::STABILIZE ,true), APMPlaneMode(APMPlaneMode::STABILIZE, true),
APMPlaneMode(APMPlaneMode::TRAINING ,true), APMPlaneMode(APMPlaneMode::TRAINING, true),
APMPlaneMode(APMPlaneMode::ACRO ,true), APMPlaneMode(APMPlaneMode::ACRO, true),
APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_A ,true), APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_A, true),
APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_B ,true), APMPlaneMode(APMPlaneMode::FLY_BY_WIRE_B, true),
APMPlaneMode(APMPlaneMode::CRUISE ,true), APMPlaneMode(APMPlaneMode::CRUISE, true),
APMPlaneMode(APMPlaneMode::AUTOTUNE ,true), APMPlaneMode(APMPlaneMode::AUTOTUNE, true),
APMPlaneMode(APMPlaneMode::AUTO ,true), APMPlaneMode(APMPlaneMode::AUTO, true),
APMPlaneMode(APMPlaneMode::RTL ,true), APMPlaneMode(APMPlaneMode::RTL, true),
APMPlaneMode(APMPlaneMode::LOITER ,true), APMPlaneMode(APMPlaneMode::LOITER, true),
APMPlaneMode(APMPlaneMode::GUIDED ,true), APMPlaneMode(APMPlaneMode::TAKEOFF, true),
APMPlaneMode(APMPlaneMode::INITIALIZING ,false), APMPlaneMode(APMPlaneMode::AVOID_ADSB, false),
APMPlaneMode(APMPlaneMode::QSTABILIZE ,true), APMPlaneMode(APMPlaneMode::GUIDED, true),
APMPlaneMode(APMPlaneMode::QHOVER ,true), APMPlaneMode(APMPlaneMode::INITIALIZING, false),
APMPlaneMode(APMPlaneMode::QLOITER ,true), APMPlaneMode(APMPlaneMode::QSTABILIZE, true),
APMPlaneMode(APMPlaneMode::QLAND ,true), APMPlaneMode(APMPlaneMode::QHOVER, true),
APMPlaneMode(APMPlaneMode::QRTL ,true), APMPlaneMode(APMPlaneMode::QLOITER, true),
APMPlaneMode(APMPlaneMode::QLAND, true),
APMPlaneMode(APMPlaneMode::QRTL, true),
APMPlaneMode(APMPlaneMode::QAUTOTUNE, true),
APMPlaneMode(APMPlaneMode::QACRO, true),
}); });
if (!_remapParamNameIntialized) { if (!_remapParamNameIntialized) {
......
...@@ -33,8 +33,8 @@ public: ...@@ -33,8 +33,8 @@ public:
AUTO = 10, AUTO = 10,
RTL = 11, RTL = 11,
LOITER = 12, LOITER = 12,
RESERVED_13 = 13, // RESERVED FOR FUTURE USE TAKEOFF = 13,
RESERVED_14 = 14, // RESERVED FOR FUTURE USE AVOID_ADSB = 14,
GUIDED = 15, GUIDED = 15,
INITIALIZING = 16, INITIALIZING = 16,
QSTABILIZE = 17, QSTABILIZE = 17,
...@@ -42,6 +42,8 @@ public: ...@@ -42,6 +42,8 @@ public:
QLOITER = 19, QLOITER = 19,
QLAND = 20, QLAND = 20,
QRTL = 21, QRTL = 21,
QAUTOTUNE = 22,
QACRO = 23,
}; };
APMPlaneMode(uint32_t mode, bool settable); APMPlaneMode(uint32_t mode, bool settable);
......
...@@ -5,6 +5,7 @@ if(BUILD_TESTING) ...@@ -5,6 +5,7 @@ if(BUILD_TESTING)
CameraCalcTest.cc CameraCalcTest.cc
CameraSectionTest.cc CameraSectionTest.cc
CorridorScanComplexItemTest.cc CorridorScanComplexItemTest.cc
FWLandingPatternTest.cc
MissionCommandTreeTest.cc MissionCommandTreeTest.cc
MissionControllerManagerTest.cc MissionControllerManagerTest.cc
MissionControllerTest.cc MissionControllerTest.cc
...@@ -30,6 +31,8 @@ add_library(MissionManager ...@@ -30,6 +31,8 @@ add_library(MissionManager
CameraSpec.cc CameraSpec.cc
ComplexMissionItem.cc ComplexMissionItem.cc
CorridorScanComplexItem.cc CorridorScanComplexItem.cc
CorridorScanPlanCreator.cc
CustomPlanCreator.cc
FixedWingLandingComplexItem.cc FixedWingLandingComplexItem.cc
GeoFenceController.cc GeoFenceController.cc
GeoFenceManager.cc GeoFenceManager.cc
...@@ -41,6 +44,7 @@ add_library(MissionManager ...@@ -41,6 +44,7 @@ add_library(MissionManager
MissionItem.cc MissionItem.cc
MissionManager.cc MissionManager.cc
MissionSettingsItem.cc MissionSettingsItem.cc
PlanCreator.cc
PlanElementController.cc PlanElementController.cc
PlanManager.cc PlanManager.cc
PlanMasterController.cc PlanMasterController.cc
...@@ -55,7 +59,9 @@ add_library(MissionManager ...@@ -55,7 +59,9 @@ add_library(MissionManager
SimpleMissionItem.cc SimpleMissionItem.cc
SpeedSection.cc SpeedSection.cc
StructureScanComplexItem.cc StructureScanComplexItem.cc
StructureScanPlanCreator.cc
SurveyComplexItem.cc SurveyComplexItem.cc
SurveyPlanCreator.cc
TransectStyleComplexItem.cc TransectStyleComplexItem.cc
VisualMissionItem.cc VisualMissionItem.cc
......
This diff is collapsed.
add_custom_target(PlanViewQml add_custom_target(PlanViewQml
SOURCES SOURCES
RallyPointMapVisuals.qml CameraCalcCamera.qml
CorridorScanEditor.qml CameraCalcGrid.qml
CameraSection.qml CameraSection.qml
SurveyMapVisual.qml CorridorScanEditor.qml
CameraCalc.qml CorridorScanMapVisual.qml
SurveyItemEditor.qml FWLandingPatternEditor.qml
RallyPointEditorHeader.qml FWLandingPatternMapVisual.qml
GeoFenceMapVisuals.qml GeoFenceEditor.qml
CorridorScanMapVisual.qml GeoFenceMapVisuals.qml
CMakeLists.txt MissionItemEditor.qml
PlanToolBarIndicators.qml MissionItemMapVisual.qml
MissionItemEditor.qml MissionItemStatus.qml
MissionItemStatus.qml MissionSettingsEditor.qml
RallyPointItemEditor.qml PlanEditToolbar.qml
PlanView.qml PlanStartOverlay.qml
FWLandingPatternMapVisual.qml PlanToolBarIndicators.qml
GeoFenceEditor.qml PlanToolBar.qml
MissionItemMapVisual.qml PlanView.qml
SimpleItemMapVisual.qml RallyPointEditorHeader.qml
StructureScanEditor.qml RallyPointItemEditor.qml
PlanToolBar.qml RallyPointMapVisuals.qml
TransectStyleComplexItemStats.qml SimpleItemEditor.qml
MissionSettingsEditor.qml SimpleItemMapVisual.qml
SimpleItemEditor.qml StructureScanEditor.qml
StructureScanMapVisual.qml StructureScanMapVisual.qml
FWLandingPatternEditor.qml SurveyItemEditor.qml
) SurveyMapVisual.qml
\ No newline at end of file TransectStyleComplexItemStats.qml
TransectStyleMapVisuals.qml
)
...@@ -158,7 +158,11 @@ static QObject* shapeFileHelperSingletonFactory(QQmlEngine*, QJSEngine*) ...@@ -158,7 +158,11 @@ static QObject* shapeFileHelperSingletonFactory(QQmlEngine*, QJSEngine*)
} }
QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
#if defined(__mobile__)
: QGuiApplication (argc, argv) : QGuiApplication (argc, argv)
#else
: QApplication (argc, argv)
#endif
, _runningUnitTests (unitTesting) , _runningUnitTests (unitTesting)
{ {
_app = this; _app = this;
......
...@@ -51,8 +51,15 @@ class QGCFileDownload; ...@@ -51,8 +51,15 @@ class QGCFileDownload;
* This class is started by the main method and provides * This class is started by the main method and provides
* the central management unit of the groundstation application. * the central management unit of the groundstation application.
* *
**/ * Needs QApplication base to support QtCharts drawing module and
class QGCApplication : public QGuiApplication * avoid application crashing on 5.12. Enforce no widget on mobile
**/
class QGCApplication :
#if defined(__mobile__)
public QGuiApplication
#else
public QApplication
#endif
{ {
Q_OBJECT Q_OBJECT
......
...@@ -25,12 +25,18 @@ Button { ...@@ -25,12 +25,18 @@ Button {
} }
property double messageHz: 0 property double messageHz: 0
property int compID: 0
contentItem: RowLayout { contentItem: RowLayout {
QGCLabel {
text: control.compID
color: checked ? qgcPal.buttonHighlightText : qgcPal.buttonText
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 3
}
QGCLabel { QGCLabel {
text: control.text text: control.text
color: checked ? qgcPal.buttonHighlightText : qgcPal.buttonText color: checked ? qgcPal.buttonHighlightText : qgcPal.buttonText
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 26 Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 28
} }
QGCLabel { QGCLabel {
color: checked ? qgcPal.buttonHighlightText : qgcPal.buttonText color: checked ? qgcPal.buttonHighlightText : qgcPal.buttonText
......
...@@ -203,8 +203,8 @@ Item { ...@@ -203,8 +203,8 @@ Item {
readonly property string groupName: modelData readonly property string groupName: modelData
onClicked: { onClicked: {
if (!checked) _rowWidth = 10
checked = true checked = true
_rowWidth = 10
controller.currentCategory = category controller.currentCategory = category
controller.currentGroup = groupName controller.currentGroup = groupName
} }
......
add_library(QtLocationPlugin add_library(QtLocationPlugin
BingMapProvider.cpp
ElevationMapProvider.cpp
EsriMapProvider.cpp
GenericMapProvider.cpp
GoogleMapProvider.cpp
MapboxMapProvider.cpp
MapProvider.cpp
QGCMapEngine.cpp QGCMapEngine.cpp
QGCMapTileSet.cpp QGCMapTileSet.cpp
QGCMapUrlEngine.cpp QGCMapUrlEngine.cpp
......
...@@ -9,10 +9,11 @@ endif() ...@@ -9,10 +9,11 @@ endif()
add_library(Vehicle add_library(Vehicle
ADSBVehicle.cc ADSBVehicle.cc
GPSRTKFactGroup.cc GPSRTKFactGroup.cc
VehicleObjectAvoidance.cc
MAVLinkLogManager.cc MAVLinkLogManager.cc
MultiVehicleManager.cc MultiVehicleManager.cc
TrajectoryPoints.cc
Vehicle.cc Vehicle.cc
VehicleObjectAvoidance.cc
${EXTRA_SRC} ${EXTRA_SRC}
) )
......
...@@ -12,6 +12,8 @@ ...@@ -12,6 +12,8 @@
#include <QLocale> #include <QLocale>
#include <QQuaternion> #include <QQuaternion>
#include <Eigen/Eigen>
#include "Vehicle.h" #include "Vehicle.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "FirmwarePluginManager.h" #include "FirmwarePluginManager.h"
...@@ -1132,15 +1134,25 @@ void Vehicle::_handleAttitudeQuaternion(mavlink_message_t& message) ...@@ -1132,15 +1134,25 @@ void Vehicle::_handleAttitudeQuaternion(mavlink_message_t& message)
mavlink_attitude_quaternion_t attitudeQuaternion; mavlink_attitude_quaternion_t attitudeQuaternion;
mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion); mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion);
Eigen::Quaternionf quat(attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4);
Eigen::Vector3f rates(attitudeQuaternion.rollspeed, attitudeQuaternion.pitchspeed, attitudeQuaternion.yawspeed);
Eigen::Quaternionf repr_offset(attitudeQuaternion.repr_offset_q[0], attitudeQuaternion.repr_offset_q[1], attitudeQuaternion.repr_offset_q[2], attitudeQuaternion.repr_offset_q[3]);
// if repr_offset is valid, rotate attitude and rates
if (repr_offset.norm() >= 0.5f) {
quat = quat * repr_offset;
rates = repr_offset * rates;
}
float roll, pitch, yaw; float roll, pitch, yaw;
float q[] = { attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4 }; float q[] = { quat.w(), quat.x(), quat.y(), quat.z() };
mavlink_quaternion_to_euler(q, &roll, &pitch, &yaw); mavlink_quaternion_to_euler(q, &roll, &pitch, &yaw);
_handleAttitudeWorker(roll, pitch, yaw); _handleAttitudeWorker(roll, pitch, yaw);
rollRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.rollspeed)); rollRate()->setRawValue(qRadiansToDegrees(rates[0]));
pitchRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.pitchspeed)); pitchRate()->setRawValue(qRadiansToDegrees(rates[1]));
yawRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.yawspeed)); yawRate()->setRawValue(qRadiansToDegrees(rates[2]));
} }
void Vehicle::_handleGpsRawInt(mavlink_message_t& message) void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
......
...@@ -12,7 +12,7 @@ ...@@ -12,7 +12,7 @@
#include "ParameterManager.h" #include "ParameterManager.h"
#include <cmath> #include <cmath>
static const char* kColPrevParam = "MPC_COL_PREV_D"; static const char* kColPrevParam = "CP_DIST";
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
VehicleObjectAvoidance::VehicleObjectAvoidance(Vehicle *vehicle, QObject* parent) VehicleObjectAvoidance::VehicleObjectAvoidance(Vehicle *vehicle, QObject* parent)
......
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