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