diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md new file mode 100644 index 0000000..382c73a --- /dev/null +++ b/CODE_OF_CONDUCT.md @@ -0,0 +1,46 @@ +# Contributor Covenant Code of Conduct + +## Our Pledge + +In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation. + +## Our Standards + +Examples of behavior that contributes to creating a positive environment include: + +* Using welcoming and inclusive language +* Being respectful of differing viewpoints and experiences +* Gracefully accepting constructive criticism +* Focusing on what is best for the community +* Showing empathy towards other community members + +Examples of unacceptable behavior by participants include: + +* The use of sexualized language or imagery and unwelcome sexual attention or advances +* Trolling, insulting/derogatory comments, and personal or political attacks +* Public or private harassment +* Publishing others' private information, such as a physical or electronic address, without explicit permission +* Other conduct which could reasonably be considered inappropriate in a professional setting + +## Our Responsibilities + +Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior. + +Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful. + +## Scope + +This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers. + +## Enforcement + +Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at lm@qgroundcontrol.org. The project team will review and investigate all complaints, and will respond in a way that it deems appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately. + +Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership. + +## Attribution + +This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [http://contributor-covenant.org/version/1/4][version] + +[homepage]: http://contributor-covenant.org +[version]: http://contributor-covenant.org/version/1/4/ diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 274cfb4..f6cd1ae 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -644,6 +644,8 @@ HEADERS += \ src/AnalyzeView/GeoTagController.h \ src/AnalyzeView/MavlinkConsoleController.h \ src/GPS/Drivers/src/gps_helper.h \ + src/GPS/Drivers/src/rtcm.h \ + src/GPS/Drivers/src/ashtech.h \ src/GPS/Drivers/src/ubx.h \ src/GPS/GPSManager.h \ src/GPS/GPSPositionMessage.h \ @@ -826,6 +828,8 @@ SOURCES += \ src/AnalyzeView/GeoTagController.cc \ src/AnalyzeView/MavlinkConsoleController.cc \ src/GPS/Drivers/src/gps_helper.cpp \ + src/GPS/Drivers/src/rtcm.cpp \ + src/GPS/Drivers/src/ashtech.cpp \ src/GPS/Drivers/src/ubx.cpp \ src/GPS/GPSManager.cc \ src/GPS/GPSProvider.cc \ diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index becf49a..9852951 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -321,12 +321,11 @@ FlightMap { visible: false property alias center: _mapCircle.center - property real radius: defaultRadius readonly property real defaultRadius: 30 function show(coord) { - orbitMapCircle.radius = defaultRadius + _mapCircle.radius.rawValue = defaultRadius orbitMapCircle.center = coord orbitMapCircle.visible = true } @@ -335,12 +334,16 @@ FlightMap { orbitMapCircle.visible = false } + function radius() { + return _mapCircle.radius.rawValue + } + Component.onCompleted: guidedActionsController.orbitMapCircle = orbitMapCircle QGCMapCircle { id: _mapCircle interactive: true - radius.rawValue: orbitMapCircle.radius + radius.rawValue: 30 } } diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 769b14a..eb98c96 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -130,7 +130,7 @@ Item { property bool _hideEmergenyStop: !QGroundControl.corePlugin.options.guidedBarShowEmergencyStop property bool _hideOrbit: !QGroundControl.corePlugin.options.guidedBarShowOrbit property bool _vehicleWasFlying: false - property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI < 255 : false + property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false //Handy code for debugging state problems property bool __debugGuidedStates: false @@ -389,7 +389,7 @@ Item { _activeVehicle.setCurrentMissionSequence(actionData) break case actionOrbit: - _activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius, _activeVehicle.altitudeAMSL.rawValue + actionAltitudeChange) + _activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius(), _activeVehicle.altitudeAMSL.rawValue + actionAltitudeChange) orbitMapCircle.hide() break case actionLandAbort: diff --git a/src/GPS/Drivers b/src/GPS/Drivers index 41223e8..d7854b7 160000 --- a/src/GPS/Drivers +++ b/src/GPS/Drivers @@ -1 +1 @@ -Subproject commit 41223e860e0f3b7fed5075be8ac17ecb7e07e428 +Subproject commit d7854b7bcf1610bb42d89f4bae553744cbe4408c diff --git a/src/GPS/GPSManager.cc b/src/GPS/GPSManager.cc index bd55d10..47e917a 100644 --- a/src/GPS/GPSManager.cc +++ b/src/GPS/GPSManager.cc @@ -26,13 +26,22 @@ GPSManager::~GPSManager() disconnectGPS(); } -void GPSManager::connectGPS(const QString& device) +void GPSManager::connectGPS(const QString& device, const QString& gps_type) { RTKSettings* rtkSettings = qgcApp()->toolbox()->settingsManager()->rtkSettings(); + GPSProvider::GPSType type; + if (gps_type.contains("trimble", Qt::CaseInsensitive)) { + type = GPSProvider::GPSType::trimble; + qCDebug(RTKGPSLog) << "Connecting Trimble device"; + } else { + type = GPSProvider::GPSType::u_blox; + qCDebug(RTKGPSLog) << "Connecting U-blox device"; + } + disconnectGPS(); _requestGpsStop = false; - _gpsProvider = new GPSProvider(device, true, rtkSettings->surveyInAccuracyLimit()->rawValue().toDouble(), rtkSettings->surveyInMinObservationDuration()->rawValue().toInt(), _requestGpsStop); + _gpsProvider = new GPSProvider(device, type, true, rtkSettings->surveyInAccuracyLimit()->rawValue().toDouble(), rtkSettings->surveyInMinObservationDuration()->rawValue().toInt(), _requestGpsStop); _gpsProvider->start(); //create RTCM device diff --git a/src/GPS/GPSManager.h b/src/GPS/GPSManager.h index e116f38..35ad573 100644 --- a/src/GPS/GPSManager.h +++ b/src/GPS/GPSManager.h @@ -28,7 +28,7 @@ public: GPSManager(QGCApplication* app, QGCToolbox* toolbox); ~GPSManager(); - void connectGPS (const QString& device); + void connectGPS (const QString& device, const QString& gps_type); void disconnectGPS (void); bool connected (void) const { return _gpsProvider && _gpsProvider->isRunning(); } diff --git a/src/GPS/GPSProvider.cc b/src/GPS/GPSProvider.cc index 8e77aa0..8a4d8d7 100644 --- a/src/GPS/GPSProvider.cc +++ b/src/GPS/GPSProvider.cc @@ -16,6 +16,7 @@ #include #include "Drivers/src/ubx.h" +#include "Drivers/src/ashtech.h" #include "Drivers/src/gps_helper.h" #include "definitions.h" @@ -53,7 +54,7 @@ void GPSProvider::run() _serial->setFlowControl(QSerialPort::NoFlowControl); unsigned int baudrate; - GPSDriverUBX* gpsDriver = nullptr; + GPSHelper* gpsDriver = nullptr; while (!_requestStop) { @@ -62,7 +63,13 @@ void GPSProvider::run() gpsDriver = nullptr; } - gpsDriver = new GPSDriverUBX(GPSDriverUBX::Interface::UART, &callbackEntry, this, &_reportGpsPos, _pReportSatInfo); + if (_type == GPSType::trimble) { + gpsDriver = new GPSDriverAshtech(&callbackEntry, this, &_reportGpsPos, _pReportSatInfo); + baudrate = 115200; + } else { + gpsDriver = new GPSDriverUBX(GPSDriverUBX::Interface::UART, &callbackEntry, this, &_reportGpsPos, _pReportSatInfo); + baudrate = 0; // auto-configure + } gpsDriver->setSurveyInSpecs(_surveyInAccMeters * 10000, _surveryInDurationSecs); if (gpsDriver->configure(baudrate, GPSDriverUBX::OutputMode::RTCM) == 0) { @@ -101,8 +108,9 @@ void GPSProvider::run() qCDebug(RTKGPSLog) << "Exiting GPS thread"; } -GPSProvider::GPSProvider(const QString& device, bool enableSatInfo, double surveyInAccMeters, int surveryInDurationSecs, const std::atomic_bool& requestStop) +GPSProvider::GPSProvider(const QString& device, GPSType type, bool enableSatInfo, double surveyInAccMeters, int surveryInDurationSecs, const std::atomic_bool& requestStop) : _device(device) + , _type(type) , _requestStop(requestStop) , _surveyInAccMeters(surveyInAccMeters) , _surveryInDurationSecs(surveryInDurationSecs) diff --git a/src/GPS/GPSProvider.h b/src/GPS/GPSProvider.h index c2b5c7e..006dd49 100644 --- a/src/GPS/GPSProvider.h +++ b/src/GPS/GPSProvider.h @@ -29,7 +29,14 @@ class GPSProvider : public QThread { Q_OBJECT public: - GPSProvider(const QString& device, bool enableSatInfo, double surveyInAccMeters, int surveryInDurationSecs, const std::atomic_bool& requestStop); + + enum class GPSType { + u_blox, + trimble + }; + + GPSProvider(const QString& device, GPSType type, bool enableSatInfo, double surveyInAccMeters, int surveryInDurationSecs, + const std::atomic_bool& requestStop); ~GPSProvider(); /** @@ -57,6 +64,7 @@ private: int callback(GPSCallbackType type, void *data1, int data2); QString _device; + GPSType _type; const std::atomic_bool& _requestStop; double _surveyInAccMeters; int _surveryInDurationSecs; diff --git a/src/GPS/vehicle_gps_position.h b/src/GPS/vehicle_gps_position.h index e8fa23d..1a3f8d3 100644 --- a/src/GPS/vehicle_gps_position.h +++ b/src/GPS/vehicle_gps_position.h @@ -63,6 +63,7 @@ struct vehicle_gps_position_s { float vel_d_m_s; float cog_rad; int32_t timestamp_time_relative; + float heading; uint8_t fix_type; bool vel_ned_valid; uint8_t satellites_used; diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc index f15e9f1..aa49406 100644 --- a/src/MissionManager/FixedWingLandingComplexItem.cc +++ b/src/MissionManager/FixedWingLandingComplexItem.cc @@ -336,8 +336,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, b complexItem->_altitudesAreRelative = landPointFrame == MAV_FRAME_GLOBAL_RELATIVE_ALT; complexItem->_loiterRadiusFact.setRawValue(qAbs(missionItemLoiter.param2())); complexItem->_loiterClockwise = missionItemLoiter.param2() > 0; - complexItem->_loiterCoordinate.setLatitude(missionItemLoiter.param5()); - complexItem->_loiterCoordinate.setLongitude(missionItemLoiter.param6()); + complexItem->setLoiterCoordinate(QGeoCoordinate(missionItemLoiter.param5(), missionItemLoiter.param6())); complexItem->_loiterAltitudeFact.setRawValue(missionItemLoiter.param7()); complexItem->_landingCoordinate.setLatitude(missionItemLand.param5()); diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index d3cbb82..a30c4cc 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -588,6 +588,14 @@ void PlanManager::_handleMissionAck(const mavlink_message_t& message) return; } + if (_vehicle->apmFirmware() && missionAck.type == MAV_MISSION_INVALID_SEQUENCE) { + // ArduPilot sends these Acks which can happen just due to noisy links causing duplicated requests being responded to. + // As far as I'm concerned this is incorrect protocol implementation but we need to deal with it anyway. So we just + // ignore it and if things really go haywire the timeouts will fire to fail the overall transaction. + qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck ArduPilot sending possibly bogus MAV_MISSION_INVALID_SEQUENCE").arg(_planTypeString()) << _planType; + return; + } + // Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what // type of a protocol sequence we are in. AckType_t savedExpectedAck = _expectedAck; diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h index caa6173..0cfb509 100644 --- a/src/MissionManager/PlanManager.h +++ b/src/MissionManager/PlanManager.h @@ -71,7 +71,7 @@ public: // These values are public so the unit test can set appropriate signal wait times // When passively waiting for a mission process, use a longer timeout. - static const int _ackTimeoutMilliseconds = 1000; + static const int _ackTimeoutMilliseconds = 1500; // When actively retrying to request mission items, use a shorter timeout instead. static const int _retryTimeoutMilliseconds = 250; static const int _maxRetryCount = 5; diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml index 041fcf4..87e6d11 100644 --- a/src/MissionManager/QGCMapPolygonVisuals.qml +++ b/src/MissionManager/QGCMapPolygonVisuals.qml @@ -38,6 +38,7 @@ Item { property var _centerDragHandleComponent property bool _circle: false property real _circleRadius + property bool _editCircleRadius: false property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2 @@ -224,7 +225,7 @@ Item { MenuItem { text: qsTr("Set radius..." ) visible: _circle - onTriggered: radiusDialog.visible = true + onTriggered: _editCircleRadius = true } MenuItem { @@ -460,18 +461,17 @@ Item { function setRadiusFromDialog() { setCircleRadius(mapPolygon.center, radiusField.text) - radiusDialog.visible = false + _editCircleRadius = false } Rectangle { - id: radiusDialog anchors.margins: _margin anchors.left: parent.right width: radiusColumn.width + (_margin *2) height: radiusColumn.height + (_margin *2) color: qgcPal.window border.color: qgcPal.text - visible: false + visible: _editCircleRadius Column { id: radiusColumn diff --git a/src/MissionManager/StructureScan.SettingsGroup.json b/src/MissionManager/StructureScan.SettingsGroup.json index 6901674..15ff6ce 100644 --- a/src/MissionManager/StructureScan.SettingsGroup.json +++ b/src/MissionManager/StructureScan.SettingsGroup.json @@ -10,16 +10,6 @@ "defaultValue": 0 }, { - "name": "GimbalYaw", - "shortDescription": "Gimbal yaw rotation.", - "type": "double", - "units": "deg", - "min": -180.0, - "max": 180.0, - "decimalPlaces": 0, - "defaultValue": 90 -}, -{ "name": "Altitude", "shortDescription": "Altitude for the bottom layer of the structure scan.", "type": "double", @@ -41,32 +31,5 @@ "units": "m", "min": 1, "defaultValue": 100 -}, -{ - "name": "Layer distance", - "shortDescription": "Distance between each layer.", - "type": "double", - "decimalPlaces": 2, - "min": 0, - "units": "m", - "defaultValue": 25 -}, -{ - "name": "Scan distance", - "shortDescription": "Scan distance away from structure.", - "type": "double", - "decimalPlaces": 2, - "min": 0, - "units": "m", - "defaultValue": 25 -}, -{ - "name": "Trigger distance", - "shortDescription": "Distance between each triggering of the camera. 0 specifies not camera trigger.", - "type": "double", - "decimalPlaces": 2, - "min": 0, - "units": "m", - "defaultValue": 25 } ] diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc index 100896e..8119c15 100644 --- a/src/MissionManager/StructureScanComplexItem.cc +++ b/src/MissionManager/StructureScanComplexItem.cc @@ -25,6 +25,7 @@ const char* StructureScanComplexItem::settingsGroup = "StructureSc const char* StructureScanComplexItem::altitudeName = "Altitude"; const char* StructureScanComplexItem::structureHeightName = "StructureHeight"; const char* StructureScanComplexItem::layersName = "Layers"; +const char* StructureScanComplexItem::gimbalPitchName = "GimbalPitch"; const char* StructureScanComplexItem::jsonComplexItemTypeValue = "StructureScan"; const char* StructureScanComplexItem::_jsonCameraCalcKey = "CameraCalc"; @@ -44,6 +45,7 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie , _altitudeFact (settingsGroup, _metaDataMap[altitudeName]) , _structureHeightFact (settingsGroup, _metaDataMap[structureHeightName]) , _layersFact (settingsGroup, _metaDataMap[layersName]) + , _gimbalPitchFact (settingsGroup, _metaDataMap[gimbalPitchName]) { _editorQml = "qrc:/qml/StructureScanEditor.qml"; @@ -51,6 +53,7 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); + connect(&_gimbalPitchFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo); connect(&_structureHeightFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo); @@ -76,6 +79,8 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots); + connect(&_cameraCalc, &CameraCalc::isManualCameraChanged, this, &StructureScanComplexItem::_updateGimbalPitch); + _recalcLayerInfo(); if (!kmlFile.isEmpty()) { @@ -147,9 +152,10 @@ void StructureScanComplexItem::save(QJsonArray& missionItems) saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; saveObject[altitudeName] = _altitudeFact.rawValue().toDouble(); - saveObject[structureHeightName] = _structureHeightFact.rawValue().toDouble(); - saveObject[_jsonAltitudeRelativeKey] = _altitudeRelative; + saveObject[structureHeightName] = _structureHeightFact.rawValue().toDouble(); + saveObject[_jsonAltitudeRelativeKey] = _altitudeRelative; saveObject[layersName] = _layersFact.rawValue().toDouble(); + saveObject[gimbalPitchName] = _gimbalPitchFact.rawValue().toDouble(); QJsonObject cameraCalcObject; _cameraCalc.save(cameraCalcObject); @@ -180,6 +186,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen { structureHeightName, QJsonValue::Double, true }, { _jsonAltitudeRelativeKey, QJsonValue::Bool, true }, { layersName, QJsonValue::Double, true }, + { gimbalPitchName, QJsonValue::Double, false }, // This value was added after initial implementation so may be missing from older files { _jsonCameraCalcKey, QJsonValue::Object, true }, }; if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) { @@ -212,6 +219,12 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen _layersFact.setRawValue (complexObject[layersName].toDouble()); _altitudeRelative = complexObject[_jsonAltitudeRelativeKey].toBool(true); + double gimbalPitchValue = 0; + if (complexObject.contains(gimbalPitchName)) { + gimbalPitchValue = complexObject[gimbalPitchName].toDouble(); + } + _gimbalPitchFact.setRawValue(gimbalPitchValue); + if (!_structurePolygon.loadFromJson(complexObject, true /* required */, errorString)) { _structurePolygon.clear(); return false; @@ -256,11 +269,12 @@ void StructureScanComplexItem::appendMissionItems(QList& items, QO MissionItem* item = new MissionItem(seqNum++, MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET, MAV_FRAME_MISSION, - 0, 0, 0, 0, // param 1-4 not used - 0, 0, // Pitch and Roll stay in standard orientation - 90, // 90 degreee yaw offset to point to structure - true, // autoContinue - false, // isCurrentItem + 0, 0, 0, 0, // param 1-4 not used + _gimbalPitchFact.rawValue().toDouble(), + 0, // Roll stays in standard orientation + 90, // 90 degreee yaw offset to point to structure + true, // autoContinue + false, // isCurrentItem missionItemParent); items.append(item); @@ -464,3 +478,10 @@ void StructureScanComplexItem::_recalcLayerInfo(void) _layersFact.setSendValueChangedSignals(true); } } + +void StructureScanComplexItem::_updateGimbalPitch(void) +{ + if (!_cameraCalc.isManualCamera()) { + _gimbalPitchFact.setRawValue(0); + } +} diff --git a/src/MissionManager/StructureScanComplexItem.h b/src/MissionManager/StructureScanComplexItem.h index 068b8a4..655f1f0 100644 --- a/src/MissionManager/StructureScanComplexItem.h +++ b/src/MissionManager/StructureScanComplexItem.h @@ -34,6 +34,7 @@ public: Q_PROPERTY(Fact* altitude READ altitude CONSTANT) Q_PROPERTY(Fact* structureHeight READ structureHeight CONSTANT) Q_PROPERTY(Fact* layers READ layers CONSTANT) + Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT) Q_PROPERTY(bool altitudeRelative READ altitudeRelative WRITE setAltitudeRelative NOTIFY altitudeRelativeChanged) Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged) Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged) @@ -44,6 +45,7 @@ public: Fact* altitude (void) { return &_altitudeFact; } Fact* structureHeight (void) { return &_structureHeightFact; } Fact* layers (void) { return &_layersFact; } + Fact* gimbalPitch (void) { return &_gimbalPitchFact; } bool altitudeRelative (void) const { return _altitudeRelative; } int cameraShots (void) const; @@ -98,6 +100,7 @@ public: static const char* altitudeName; static const char* structureHeightName; static const char* layersName; + static const char* gimbalPitchName; signals: void cameraShotsChanged (int cameraShots); @@ -114,6 +117,7 @@ private slots: void _recalcCameraShots (void); void _recalcLayerInfo (void); void _updateLastSequenceNumber (void); + void _updateGimbalPitch (void); private: void _setExitCoordinate(const QGeoCoordinate& coordinate); @@ -141,6 +145,7 @@ private: SettingsFact _altitudeFact; SettingsFact _structureHeightFact; SettingsFact _layersFact; + SettingsFact _gimbalPitchFact; static const char* _jsonCameraCalcKey; static const char* _jsonAltitudeRelativeKey; diff --git a/src/PlanView/FWLandingPatternMapVisual.qml b/src/PlanView/FWLandingPatternMapVisual.qml index c16b3e0..8a7ca65 100644 --- a/src/PlanView/FWLandingPatternMapVisual.qml +++ b/src/PlanView/FWLandingPatternMapVisual.qml @@ -159,7 +159,8 @@ Item { id: mouseAreaComponent MouseArea { - anchors.fill: map + anchors.fill: map + z: QGroundControl.zOrderMapItems + 1 // Over item indicators onClicked: { var coordinate = map.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */) diff --git a/src/PlanView/StructureScanEditor.qml b/src/PlanView/StructureScanEditor.qml index 9974da5..355ce08 100644 --- a/src/PlanView/StructureScanEditor.qml +++ b/src/PlanView/StructureScanEditor.qml @@ -126,6 +126,16 @@ Rectangle { Layout.fillWidth: true } + QGCLabel { + text: qsTr("Gimbal pitch") + visible: missionItem.cameraCalc.isManualCamera + } + FactTextField { + fact: missionItem.gimbalPitch + Layout.fillWidth: true + visible: missionItem.cameraCalc.isManualCamera + } + QGCCheckBox { text: qsTr("Relative altitude") checked: missionItem.altitudeRelative diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f17b9fb..8651ba4 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -113,7 +113,7 @@ Vehicle::Vehicle(LinkInterface* link, , _currentMessageType(MessageNone) , _updateCount(0) , _rcRSSI(255) - , _rcRSSIstore(255) + , _rcRSSIstore(255.) , _autoDisconnect(false) , _flying(false) , _landing(false) @@ -313,7 +313,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _currentMessageType(MessageNone) , _updateCount(0) , _rcRSSI(255) - , _rcRSSIstore(255) + , _rcRSSIstore(255.) , _autoDisconnect(false) , _flying(false) , _landing(false) @@ -2475,10 +2475,18 @@ void Vehicle::_imageReady(UASInterface*) void Vehicle::_remoteControlRSSIChanged(uint8_t rssi) { - if (_rcRSSIstore < 0 || _rcRSSIstore > 100) { - _rcRSSIstore = rssi; + //-- 0 <= rssi <= 100 - 255 means "invalid/unknown" + if(rssi > 100) { // Anything over 100 doesn't make sense + if(_rcRSSI != 255) { + _rcRSSI = 255; + emit rcRSSIChanged(_rcRSSI); + } + return; + } + //-- Initialize it + if(_rcRSSIstore == 255.) { + _rcRSSIstore = (double)rssi; } - // Low pass to git rid of jitter _rcRSSIstore = (_rcRSSIstore * 0.9f) + ((float)rssi * 0.1); uint8_t filteredRSSI = (uint8_t)ceil(_rcRSSIstore); diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index ada53b2..0030c27 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -586,7 +586,7 @@ void LinkManager::_updateAutoConnectLinks(void) if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !_toolbox->gpsManager()->connected()) { qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed(); _autoConnectRTKPort = portInfo.systemLocation(); - _toolbox->gpsManager()->connectGPS(portInfo.systemLocation()); + _toolbox->gpsManager()->connectGPS(portInfo.systemLocation(), boardName); } break; #endif diff --git a/src/comm/USBBoardInfo.json b/src/comm/USBBoardInfo.json index dd24ff6..f68a71f 100644 --- a/src/comm/USBBoardInfo.json +++ b/src/comm/USBBoardInfo.json @@ -27,7 +27,8 @@ { "vendorID": 1027, "productID": 24577, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "3DR Radio on FTDI" }, { "vendorID": 4292, "productID": 60000, "boardClass": "SiK Radio", "name": "SiK Radio", "comment": "SILabs Radio" }, - { "vendorID": 5446, "productID": 424, "boardClass": "RTK GPS", "name": "RTK GPS", "comment": "Ublox RTK GPS" }, + { "vendorID": 5446, "productID": 424, "boardClass": "RTK GPS", "name": "U-blox RTK GPS", "comment": "U-blox RTK GPS" }, + { "vendorID": 1317, "productID": 42151, "boardClass": "RTK GPS", "name": "Trimble RTK GPS", "comment": "Trimble RTK GPS" }, { "vendorID": 8352, "productID": 16732, "boardClass": "OpenPilot", "name": "OpenPilot OPLink" }, { "vendorID": 8352, "productID": 16733, "boardClass": "OpenPilot", "name": "OpenPilot CC3D" }, diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 2a3c6b6..a82c319 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -402,7 +402,7 @@ QGCView { anchors.horizontalCenter: parent.horizontalCenter columns: 2 - QGCLabel { text: qsTr("Survey in accuracy") } + QGCLabel { text: qsTr("Survey in accuracy (U-blox only)") } FactTextField { Layout.preferredWidth: _valueFieldWidth fact: QGroundControl.settingsManager.rtkSettings.surveyInAccuracyLimit diff --git a/src/ui/toolbar/GPSRTKIndicator.qml b/src/ui/toolbar/GPSRTKIndicator.qml index 7dfe170..767278b 100644 --- a/src/ui/toolbar/GPSRTKIndicator.qml +++ b/src/ui/toolbar/GPSRTKIndicator.qml @@ -69,9 +69,11 @@ Item { QGCLabel { // during survey-in show the current accuracy, after that show the final accuracy text: QGroundControl.gpsRtk.valid.value ? qsTr("Accuracy:") : qsTr("Current Accuracy:") + visible: QGroundControl.gpsRtk.currentAccuracy.value > 0 } QGCLabel { text: QGroundControl.gpsRtk.currentAccuracy.valueString + " " + QGroundControl.appSettingsDistanceUnitsString + visible: QGroundControl.gpsRtk.currentAccuracy.value > 0 } QGCLabel { text: qsTr("Satellites:") } QGCLabel { text: QGroundControl.gpsRtk.numSatellites.value } diff --git a/src/ui/toolbar/RCRSSIIndicator.qml b/src/ui/toolbar/RCRSSIIndicator.qml index baf04b1..aaed481 100644 --- a/src/ui/toolbar/RCRSSIIndicator.qml +++ b/src/ui/toolbar/RCRSSIIndicator.qml @@ -26,7 +26,8 @@ Item { anchors.bottom: parent.bottom visible: _activeVehicle ? _activeVehicle.supportsRadio : true - property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false Component { id: rcRSSIInfo @@ -54,7 +55,7 @@ Item { GridLayout { id: rcrssiGrid - visible: _activeVehicle && _activeVehicle.rcRSSI != 255 + visible: _rcRSSIAvailable anchors.margins: ScreenTools.defaultFontPixelHeight columnSpacing: ScreenTools.defaultFontPixelWidth columns: 2 @@ -86,14 +87,14 @@ Item { sourceSize.height: height source: "/qmlimages/RC.svg" fillMode: Image.PreserveAspectFit - opacity: _activeVehicle ? (((_activeVehicle.rcRSSI < 0) || (_activeVehicle.rcRSSI > 100)) ? 0.5 : 1) : 0.5 + opacity: _rcRSSIAvailable ? 1 : 0.5 color: qgcPal.buttonText } SignalStrength { anchors.verticalCenter: parent.verticalCenter size: parent.height * 0.5 - percent: _activeVehicle ? ((_activeVehicle.rcRSSI > 100) ? 0 : _activeVehicle.rcRSSI) : 0 + percent: _rcRSSIAvailable ? _activeVehicle.rcRSSI : 0 } }