Commit a3b3e582 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into foo

# Conflicts:
#	src/FlightDisplay/GuidedActionsController.qml
#	src/PlanView/PlanView.qml
parents 6cc84cd5 28b58527
...@@ -50,23 +50,11 @@ build_script: ...@@ -50,23 +50,11 @@ build_script:
test_script: test_script:
- if "%CONFIG%" EQU "debug" ( %SHADOW_BUILD_DIR%\debug\qgroundcontrol --unittest ) - if "%CONFIG%" EQU "debug" ( %SHADOW_BUILD_DIR%\debug\qgroundcontrol --unittest )
for: artifacts:
-
branches:
only:
- master
artifacts:
- path: QGroundControl-installer.exe - path: QGroundControl-installer.exe
name: qgcinstaller name: qgcinstaller
- - path: build_windows_install\release\qgroundcontrol.pdb
branches: name: pdb
only:
- Stable_V3.5
artifacts:
- path: QGroundControl-installer.exe
name: qgcinstaller
- path: symbols\**\*.*_
name: symbols
deploy: deploy:
# deploy continuous builds to s3 # deploy continuous builds to s3
...@@ -101,19 +89,19 @@ deploy: ...@@ -101,19 +89,19 @@ deploy:
# appveyor_repo_tag: false # appveyor_repo_tag: false
# deploy release symbols to s3 # deploy release symbols to s3
- provider: S3 # - provider: S3
access_key_id: # access_key_id:
secure: IGAojLMqokL+76DbdulmWDA3MTsxEBBi3ReVVSqTy9c= # secure: IGAojLMqokL+76DbdulmWDA3MTsxEBBi3ReVVSqTy9c=
secret_access_key: # secret_access_key:
secure: RiYqaR+3T2PMNz2j5ur8LCA6H/Zfd4jTX33CZE5iBxm+zaz4QLs25p0B7prpaoNN # secure: RiYqaR+3T2PMNz2j5ur8LCA6H/Zfd4jTX33CZE5iBxm+zaz4QLs25p0B7prpaoNN
bucket: qgroundcontrol # bucket: qgroundcontrol
region: us-west-2 # region: us-west-2
set_public: true # set_public: true
folder: releasesyms # folder: releasesyms
artifact: symbols # artifact: symbols
on: # on:
CONFIG: installer # CONFIG: installer
appveyor_repo_tag: true # appveyor_repo_tag: true
# deploy tagged releases to Github releases # deploy tagged releases to Github releases
- provider: GitHub - provider: GitHub
...@@ -155,3 +143,18 @@ deploy: ...@@ -155,3 +143,18 @@ deploy:
on: on:
CONFIG: installer CONFIG: installer
appveyor_repo_tag: true appveyor_repo_tag: true
# deploy pdb for tagged releases to s3 latest folder
- provider: S3
access_key_id:
secure: IGAojLMqokL+76DbdulmWDA3MTsxEBBi3ReVVSqTy9c=
secret_access_key:
secure: RiYqaR+3T2PMNz2j5ur8LCA6H/Zfd4jTX33CZE5iBxm+zaz4QLs25p0B7prpaoNN
bucket: qgroundcontrol
region: us-west-2
set_public: true
folder: latest
artifact: pdb
on:
CONFIG: installer
appveyor_repo_tag: true
...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build ### 3.6.0 - Daily Build
* Plan/Pattern: Support named presets to simplify commonly used settings setup. Currently only supported by Survey.
* ArduCopter: Handle 3.7 parameter name change from CH#_OPT to RC#_OPTION. * ArduCopter: Handle 3.7 parameter name change from CH#_OPT to RC#_OPTION.
* Improved support for flashing/connecting to ChibiOS bootloaders boards. * Improved support for flashing/connecting to ChibiOS bootloaders boards.
* Making the camera API available to all firmwares, not just PX4. * Making the camera API available to all firmwares, not just PX4.
...@@ -13,6 +14,7 @@ Note: This file only contains high level features or important fixes. ...@@ -13,6 +14,7 @@ Note: This file only contains high level features or important fixes.
* Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans. * Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans.
### 3.5.1 - Not yet released ### 3.5.1 - Not yet released
* Add ArduPilot CubeBlack Service Bulletin check
* Fix visibility of PX4/ArduPilot logo in toolbar * Fix visibility of PX4/ArduPilot logo in toolbar
* Fix tile set count but in OfflineMaps which would cause image and elevation tile set to have incorrect counts and be incorrectly marked as download incomplete. * Fix tile set count but in OfflineMaps which would cause image and elevation tile set to have incorrect counts and be incorrectly marked as download incomplete.
......
...@@ -210,6 +210,7 @@ ...@@ -210,6 +210,7 @@
</qresource> </qresource>
<qresource prefix="/json"> <qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file> <file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
<file alias="BreachReturn.FactMetaData.json">src/MissionManager/BreachReturn.FactMetaData.json</file>
<file alias="CameraCalc.FactMetaData.json">src/MissionManager/CameraCalc.FactMetaData.json</file> <file alias="CameraCalc.FactMetaData.json">src/MissionManager/CameraCalc.FactMetaData.json</file>
<file alias="CameraSpec.FactMetaData.json">src/MissionManager/CameraSpec.FactMetaData.json</file> <file alias="CameraSpec.FactMetaData.json">src/MissionManager/CameraSpec.FactMetaData.json</file>
<file alias="CorridorScan.SettingsGroup.json">src/MissionManager/CorridorScan.SettingsGroup.json</file> <file alias="CorridorScan.SettingsGroup.json">src/MissionManager/CorridorScan.SettingsGroup.json</file>
......
...@@ -29,6 +29,11 @@ ...@@ -29,6 +29,11 @@
#include "APMSubFrameComponent.h" #include "APMSubFrameComponent.h"
#include "ESP8266Component.h" #include "ESP8266Component.h"
#include "APMHeliComponent.h" #include "APMHeliComponent.h"
#include "QGCApplication.h"
#if !defined(NO_SERIAL_LINK) && !defined(__android__)
#include <QSerialPortInfo>
#endif
/// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type. /// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type.
APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent)
...@@ -50,6 +55,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) ...@@ -50,6 +55,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent)
, _heliComponent (NULL) , _heliComponent (NULL)
{ {
APMAirframeLoader::loadAirframeFactMetaData(); APMAirframeLoader::loadAirframeFactMetaData();
#if !defined(NO_SERIAL_LINK) && !defined(__android__)
connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack);
#endif
} }
APMAutoPilotPlugin::~APMAutoPilotPlugin() APMAutoPilotPlugin::~APMAutoPilotPlugin()
...@@ -170,3 +179,34 @@ QString APMAutoPilotPlugin::prerequisiteSetup(VehicleComponent* component) const ...@@ -170,3 +179,34 @@ QString APMAutoPilotPlugin::prerequisiteSetup(VehicleComponent* component) const
return QString(); return QString();
} }
#if !defined(NO_SERIAL_LINK) && !defined(__android__)
/// The following code is executed when the Vehicle is parameter ready. It checks for the service bulletin against Cube Blacks.
void APMAutoPilotPlugin::_checkForBadCubeBlack(void)
{
bool cubeBlackFound = false;
for (const QVariant& varLink: _vehicle->links()) {
SerialLink* serialLink = varLink.value<SerialLink*>();
if (serialLink && QSerialPortInfo(*serialLink->_hackAccessToPort()).description().contains(QStringLiteral("CubeBlack"))) {
cubeBlackFound = true;
}
}
if (!cubeBlackFound) {
return;
}
ParameterManager* paramMgr = _vehicle->parameterManager();
QString paramAcc3("INS_ACC3_ID");
QString paramGyr3("INS_GYR3_ID");
QString paramEnableMask("INS_ENABLE_MASK");
if (paramMgr->parameterExists(-1, paramAcc3) && paramMgr->getParameter(-1, paramAcc3)->rawValue().toInt() == 0 &&
paramMgr->parameterExists(-1, paramGyr3) && paramMgr->getParameter(-1, paramGyr3)->rawValue().toInt() == 0 &&
paramMgr->parameterExists(-1, paramEnableMask) && paramMgr->getParameter(-1, paramEnableMask)->rawValue().toInt() >= 7) {
qgcApp()->showMessage(tr("WARNING: The flight board you are using has a critical service bulletin against ti which advise against flying. https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406"));
}
}
#endif
...@@ -59,6 +59,11 @@ protected: ...@@ -59,6 +59,11 @@ protected:
ESP8266Component* _esp8266Component; ESP8266Component* _esp8266Component;
APMHeliComponent* _heliComponent; APMHeliComponent* _heliComponent;
#if !defined(NO_SERIAL_LINK) && !defined(__android__)
private slots:
void _checkForBadCubeBlack(void);
#endif
private: private:
QVariantList _components; QVariantList _components;
}; };
......
...@@ -44,6 +44,8 @@ SetupPage { ...@@ -44,6 +44,8 @@ SetupPage {
property bool _batt2ParamsAvailable: controller.parameterExists(-1, "BATT2_CAPACITY") property bool _batt2ParamsAvailable: controller.parameterExists(-1, "BATT2_CAPACITY")
property bool _showBatt1Reboot: _batt1MonitorEnabled && !_batt1ParamsAvailable property bool _showBatt1Reboot: _batt1MonitorEnabled && !_batt1ParamsAvailable
property bool _showBatt2Reboot: _batt2MonitorEnabled && !_batt2ParamsAvailable property bool _showBatt2Reboot: _batt2MonitorEnabled && !_batt2ParamsAvailable
property bool _escCalibrationAvailable: controller.parameterExists(-1, "ESC_CALIBRATION")
property Fact _escCalibration: controller.getParameterFact(-1, "ESC_CALIBRATION", false /* reportMissing */)
property string _restartRequired: qsTr("Requires vehicle reboot") property string _restartRequired: qsTr("Requires vehicle reboot")
...@@ -216,6 +218,61 @@ SetupPage { ...@@ -216,6 +218,61 @@ SetupPage {
} }
} }
} }
Column {
spacing: _margins / 2
visible: _escCalibrationAvailable
QGCLabel {
text: qsTr("ESC Calibration")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
width: escCalibrationHolder.x + escCalibrationHolder.width + _margins
height: escCalibrationHolder.y + escCalibrationHolder.height + _margins
color: ggcPal.windowShade
Column {
id: escCalibrationHolder
x: _margins
y: _margins
spacing: _margins
Column {
spacing: _margins
QGCLabel {
text: qsTr("WARNING: Remove props prior to calibration!")
color: qgcPal.warningText
}
Row {
spacing: _margins
QGCButton {
text: qsTr("Calibrate")
enabled: _escCalibration.rawValue === 0
onClicked: _escCalibration.rawValue = 3
}
Column {
enabled: _escCalibration.rawValue === 3
QGCLabel { text: _escCalibration.rawValue === 3 ? qsTr("Now perform these steps:") : qsTr("Click Calibrate to start, then:") }
QGCLabel { text: qsTr("- Disconnect USB and battery so flight controller powers down") }
QGCLabel { text: qsTr("- Connect the battery") }
QGCLabel { text: qsTr("- The arming tone will be played (if the vehicle has a buzzer attached)") }
QGCLabel { text: qsTr("- If using a flight controller with a safety button press it until it displays solid red") }
QGCLabel { text: qsTr("- You will hear a musical tone then two beeps") }
QGCLabel { text: qsTr("- A few seconds later you should hear a number of beeps (one for each battery cell you’re using)") }
QGCLabel { text: qsTr("- And finally a single long beep indicating the end points have been set and the ESC is calibrated") }
QGCLabel { text: qsTr("- Disconnect the battery and power up again normally") }
}
}
}
}
}
}
} // Flow } // Flow
} // Component - powerPageComponent } // Component - powerPageComponent
......
...@@ -897,9 +897,9 @@ void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord ...@@ -897,9 +897,9 @@ void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
vehicle->missionManager()->writeArduPilotGuidedMissionItem(coordWithAltitude, false /* altChangeOnly */); vehicle->missionManager()->writeArduPilotGuidedMissionItem(coordWithAltitude, false /* altChangeOnly */);
} }
void APMFirmwarePlugin::guidedModeRTL(Vehicle* vehicle) void APMFirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
{ {
_setFlightModeAndValidate(vehicle, rtlFlightMode()); _setFlightModeAndValidate(vehicle, smartRTL ? smartRTLFlightMode() : rtlFlightMode());
} }
void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
......
...@@ -86,9 +86,10 @@ public: ...@@ -86,9 +86,10 @@ public:
bool isGuidedMode (const Vehicle* vehicle) const override; bool isGuidedMode (const Vehicle* vehicle) const override;
QString gotoFlightMode (void) const override { return QStringLiteral("Guided"); } QString gotoFlightMode (void) const override { return QStringLiteral("Guided"); }
QString rtlFlightMode (void) const override { return QString("RTL"); } QString rtlFlightMode (void) const override { return QString("RTL"); }
QString smartRTLFlightMode (void) const override { return QString("Smart RTL"); }
QString missionFlightMode (void) const override { return QString("Auto"); } QString missionFlightMode (void) const override { return QString("Auto"); }
void pauseVehicle (Vehicle* vehicle) override; void pauseVehicle (Vehicle* vehicle) override;
void guidedModeRTL (Vehicle* vehicle) override; void guidedModeRTL (Vehicle* vehicle, bool smartRTL) override;
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeChange) override; void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeChange) override;
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override; bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override;
void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) override; void adjustOutgoingMavlinkMessage (Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message) override;
......
...@@ -23,26 +23,25 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : ...@@ -23,26 +23,25 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode(mode, settable) APMCustomMode(mode, settable)
{ {
QMap<uint32_t,QString> enumToString; QMap<uint32_t,QString> enumToString;
enumToString.insert(STABILIZE, "Stabilize"); enumToString.insert(STABILIZE, "Stabilize");
enumToString.insert(ACRO, "Acro"); enumToString.insert(ACRO, "Acro");
enumToString.insert(ALT_HOLD, "Altitude Hold"); enumToString.insert(ALT_HOLD, "Altitude Hold");
enumToString.insert(AUTO, "Auto"); enumToString.insert(AUTO, "Auto");
enumToString.insert(GUIDED, "Guided"); enumToString.insert(GUIDED, "Guided");
enumToString.insert(LOITER, "Loiter"); enumToString.insert(LOITER, "Loiter");
enumToString.insert(RTL, "RTL"); enumToString.insert(RTL, "RTL");
enumToString.insert(CIRCLE, "Circle"); enumToString.insert(CIRCLE, "Circle");
enumToString.insert(LAND, "Land"); enumToString.insert(LAND, "Land");
enumToString.insert(DRIFT, "Drift"); enumToString.insert(DRIFT, "Drift");
enumToString.insert(SPORT, "Sport"); enumToString.insert(SPORT, "Sport");
enumToString.insert(FLIP, "Flip"); enumToString.insert(FLIP, "Flip");
enumToString.insert(AUTOTUNE, "Autotune"); enumToString.insert(AUTOTUNE, "Autotune");
enumToString.insert(POS_HOLD, "Position Hold"); enumToString.insert(POS_HOLD, "Position Hold");
enumToString.insert(BRAKE, "Brake"); enumToString.insert(BRAKE, "Brake");
enumToString.insert(THROW, "Throw"); enumToString.insert(THROW, "Throw");
enumToString.insert(AVOID_ADSB,"Avoid ADSB"); enumToString.insert(AVOID_ADSB, "Avoid ADSB");
enumToString.insert(GUIDED_NOGPS,"Guided No GPS"); enumToString.insert(GUIDED_NOGPS, "Guided No GPS");
enumToString.insert(SAFE_RTL,"Smart RTL"); enumToString.insert(SAFE_RTL, "Smart RTL");
setEnumToStringMapping(enumToString); setEnumToStringMapping(enumToString);
} }
......
...@@ -65,8 +65,9 @@ public: ...@@ -65,8 +65,9 @@ public:
QString pauseFlightMode (void) const override { return QString("Brake"); } QString pauseFlightMode (void) const override { return QString("Brake"); }
QString landFlightMode (void) const override { return QString("Land"); } QString landFlightMode (void) const override { return QString("Land"); }
QString takeControlFlightMode (void) const override { return QString("Loiter"); } QString takeControlFlightMode (void) const override { return QString("Loiter"); }
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const final; bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; }
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;
......
...@@ -49,8 +49,9 @@ public: ...@@ -49,8 +49,9 @@ public:
QString pauseFlightMode (void) const override { return QString("Hold"); } QString pauseFlightMode (void) const override { return QString("Hold"); }
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeChange) final; void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeChange) final;
int remapParamNameHigestMinorVersionNumber (int majorVersionNumber) const final; int remapParamNameHigestMinorVersionNumber (int majorVersionNumber) const final;
const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; } const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
bool supportsNegativeThrust(void) final; bool supportsNegativeThrust (void) final;
bool supportsSmartRTL (void) const override { return true; }
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;
......
...@@ -240,10 +240,11 @@ void FirmwarePlugin::pauseVehicle(Vehicle* vehicle) ...@@ -240,10 +240,11 @@ void FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
} }
void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle) void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
{ {
// Not supported by generic vehicle // Not supported by generic vehicle
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(smartRTL);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
} }
......
...@@ -105,6 +105,11 @@ public: ...@@ -105,6 +105,11 @@ public:
/// Returns the flight mode for RTL /// Returns the flight mode for RTL
virtual QString rtlFlightMode(void) const { return QString(); } virtual QString rtlFlightMode(void) const { return QString(); }
/// Returns the flight mode for Smart RTL
virtual QString smartRTLFlightMode(void) const { return QString(); }
virtual bool supportsSmartRTL(void) const { return false; }
/// Returns the flight mode for Land /// Returns the flight mode for Land
virtual QString landFlightMode(void) const { return QString(); } virtual QString landFlightMode(void) const { return QString(); }
...@@ -125,7 +130,7 @@ public: ...@@ -125,7 +130,7 @@ public:
virtual void pauseVehicle(Vehicle* vehicle); virtual void pauseVehicle(Vehicle* vehicle);
/// Command vehicle to return to launch /// Command vehicle to return to launch
virtual void guidedModeRTL(Vehicle* vehicle); virtual void guidedModeRTL(Vehicle* vehicle, bool smartRTL);
/// Command vehicle to land at current location /// Command vehicle to land at current location
virtual void guidedModeLand(Vehicle* vehicle); virtual void guidedModeLand(Vehicle* vehicle);
......
...@@ -351,8 +351,9 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle) ...@@ -351,8 +351,9 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
NAN); NAN);
} }
void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle) void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
{ {
Q_UNUSED(smartRTL);
_setFlightModeAndValidate(vehicle, _rtlFlightMode); _setFlightModeAndValidate(vehicle, _rtlFlightMode);
} }
......
...@@ -44,7 +44,7 @@ public: ...@@ -44,7 +44,7 @@ public:
QString takeControlFlightMode (void) const override { return _manualFlightMode; } QString takeControlFlightMode (void) const override { return _manualFlightMode; }
QString gotoFlightMode (void) const override { return _holdFlightMode; } QString gotoFlightMode (void) const override { return _holdFlightMode; }
void pauseVehicle (Vehicle* vehicle) override; void pauseVehicle (Vehicle* vehicle) override;
void guidedModeRTL (Vehicle* vehicle) override; void guidedModeRTL (Vehicle* vehicle, bool smartRTL) override;
void guidedModeLand (Vehicle* vehicle) override; void guidedModeLand (Vehicle* vehicle) override;
void guidedModeTakeoff (Vehicle* vehicle, double takeoffAltRel) override; void guidedModeTakeoff (Vehicle* vehicle, double takeoffAltRel) override;
void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) override; void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) override;
......
...@@ -1083,7 +1083,7 @@ This parameter controls the time constant of the decay</short_desc> ...@@ -1083,7 +1083,7 @@ This parameter controls the time constant of the decay</short_desc>
</parameter> </parameter>
<parameter default="1" name="EKF2_AID_MASK" type="INT32"> <parameter default="1" name="EKF2_AID_MASK" type="INT32">
<short_desc>Integer bitmask controlling data fusion and aiding methods</short_desc> <short_desc>Integer bitmask controlling data fusion and aiding methods</short_desc>
<long_desc>Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true.</long_desc> <long_desc>Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU delta velocity bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true.</long_desc>
<min>0</min> <min>0</min>
<max>255</max> <max>255</max>
<reboot_required>true</reboot_required> <reboot_required>true</reboot_required>
...@@ -4471,15 +4471,6 @@ default 1.5 turns per second</short_desc> ...@@ -4471,15 +4471,6 @@ default 1.5 turns per second</short_desc>
<decimal>2</decimal> <decimal>2</decimal>
<increment>0.01</increment> <increment>0.01</increment>
</parameter> </parameter>
<parameter default="45.0" name="MC_YAWRAUTO_MAX" type="FLOAT">
<short_desc>Max yaw rate in auto mode</short_desc>
<long_desc>Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.</long_desc>
<min>0.0</min>
<max>360.0</max>
<unit>deg/s</unit>
<decimal>1</decimal>
<increment>5</increment>
</parameter>
<parameter default="2.8" name="MC_YAW_P" type="FLOAT"> <parameter default="2.8" name="MC_YAW_P" type="FLOAT">
<short_desc>Yaw P gain</short_desc> <short_desc>Yaw P gain</short_desc>
<long_desc>Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc> <long_desc>Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.</long_desc>
...@@ -4496,6 +4487,15 @@ default 1.5 turns per second</short_desc> ...@@ -4496,6 +4487,15 @@ default 1.5 turns per second</short_desc>
<decimal>2</decimal> <decimal>2</decimal>
<increment>0.01</increment> <increment>0.01</increment>
</parameter> </parameter>
<parameter default="45.0" name="MPC_YAWRAUTO_MAX" type="FLOAT">
<short_desc>Max yaw rate in auto mode</short_desc>
<long_desc>Limit the rate of change of the yaw setpoint in autonomous mode to avoid large control output and mixer saturation.</long_desc>
<min>0.0</min>
<max>360.0</max>
<unit>deg/s</unit>
<decimal>1</decimal>
<increment>5</increment>
</parameter>
</group> </group>
<group name="Multicopter Position Control"> <group name="Multicopter Position Control">
<parameter default="10.0" name="MPC_ACC_DOWN_MAX" type="FLOAT"> <parameter default="10.0" name="MPC_ACC_DOWN_MAX" type="FLOAT">
......
...@@ -35,6 +35,8 @@ Rectangle { ...@@ -35,6 +35,8 @@ Rectangle {
property var actionData property var actionData
property bool hideTrigger: false property bool hideTrigger: false
property var mapIndicator property var mapIndicator
property alias optionText: optionCheckBox.text
property alias optionChecked: optionCheckBox.checked
property real _margins: ScreenTools.defaultFontPixelWidth property real _margins: ScreenTools.defaultFontPixelWidth
property bool _emergencyAction: action === guidedController.actionEmergencyStop property bool _emergencyAction: action === guidedController.actionEmergencyStop
...@@ -101,6 +103,13 @@ Rectangle { ...@@ -101,6 +103,13 @@ Rectangle {
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
} }
QGCCheckBox {
id: optionCheckBox
anchors.horizontalCenter: parent.horizontalCenter
text: ""
visible: text !== ""
}
// Action confirmation control // Action confirmation control
SliderSwitch { SliderSwitch {
id: slider id: slider
...@@ -115,7 +124,7 @@ Rectangle { ...@@ -115,7 +124,7 @@ Rectangle {
altitudeSlider.visible = false altitudeSlider.visible = false
} }
hideTrigger = false hideTrigger = false
guidedController.executeAction(_root.action, _root.actionData, altitudeChange) guidedController.executeAction(_root.action, _root.actionData, altitudeChange, _root.optionChecked)
if (mapIndicator) { if (mapIndicator) {
mapIndicator.actionConfirmed() mapIndicator.actionConfirmed()
mapIndicator = undefined mapIndicator = undefined
......
...@@ -208,7 +208,7 @@ Item { ...@@ -208,7 +208,7 @@ Item {
on_FlightModeChanged: { on_FlightModeChanged: {
_vehiclePaused = activeVehicle ? _flightMode === activeVehicle.pauseFlightMode : false _vehiclePaused = activeVehicle ? _flightMode === activeVehicle.pauseFlightMode : false
_vehicleInRTLMode = activeVehicle ? _flightMode === activeVehicle.rtlFlightMode : false _vehicleInRTLMode = activeVehicle ? _flightMode === activeVehicle.rtlFlightMode || _flightMode === activeVehicle.smartRTLFlightMode : false
_vehicleInLandMode = activeVehicle ? _flightMode === activeVehicle.landFlightMode : false _vehicleInLandMode = activeVehicle ? _flightMode === activeVehicle.landFlightMode : false
_vehicleInMissionMode = activeVehicle ? _flightMode === activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups _vehicleInMissionMode = activeVehicle ? _flightMode === activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups
} }
...@@ -221,6 +221,7 @@ Item { ...@@ -221,6 +221,7 @@ Item {
confirmDialog.actionData = actionData confirmDialog.actionData = actionData
confirmDialog.hideTrigger = true confirmDialog.hideTrigger = true
confirmDialog.mapIndicator = mapIndicator confirmDialog.mapIndicator = mapIndicator
confirmDialog.optionText = ""
_actionData = actionData _actionData = actionData
switch (actionCode) { switch (actionCode) {
case actionArm: case actionArm:
...@@ -284,6 +285,10 @@ Item { ...@@ -284,6 +285,10 @@ Item {
case actionRTL: case actionRTL:
confirmDialog.title = rtlTitle confirmDialog.title = rtlTitle
confirmDialog.message = rtlMessage confirmDialog.message = rtlMessage
if (activeVehicle.supportsSmartRTL) {
confirmDialog.optionText = qsTr("Smart RTL")
confirmDialog.optionChecked = false
}
confirmDialog.hideTrigger = Qt.binding(function() { return !showRTL }) confirmDialog.hideTrigger = Qt.binding(function() { return !showRTL })
break; break;
case actionChangeAlt: case actionChangeAlt:
...@@ -344,12 +349,12 @@ Item { ...@@ -344,12 +349,12 @@ Item {
} }
// Executes the specified action // Executes the specified action
function executeAction(actionCode, actionData, actionAltitudeChange) { function executeAction(actionCode, actionData, actionAltitudeChange, optionChecked) {
var i; var i;
var rgVehicle; var rgVehicle;
switch (actionCode) { switch (actionCode) {
case actionRTL: case actionRTL:
activeVehicle.guidedModeRTL() activeVehicle.guidedModeRTL(optionChecked)
break break
case actionLand: case actionLand:
activeVehicle.guidedModeLand() activeVehicle.guidedModeLand()
......
[
{
"name": "Latitude",
"shortDescription": "Latitude of breach return point position",
"type": "double",
"decimalPlaces": 7
},
{
"name": "Longitude",
"shortDescription": "Longitude of breach return point position",
"type": "double",
"decimalPlaces": 7
},
{
"name": "Altitude",
"shortDescription": "Altitude of breach return point position (Rel)",
"type": "double",
"decimalPlaces": 2,
"units": "m"
}
]
...@@ -95,7 +95,7 @@ void CameraCalc::_cameraNameChanged(void) ...@@ -95,7 +95,7 @@ void CameraCalc::_cameraNameChanged(void)
// Validate known camera name // Validate known camera name
bool foundKnownCamera = false; bool foundKnownCamera = false;
CameraMetaData* cameraMetaData = NULL; CameraMetaData* cameraMetaData = nullptr;
if (!isManualCamera() && !isCustomCamera()) { if (!isManualCamera() && !isCustomCamera()) {
for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) { for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) {
cameraMetaData = _knownCameraList[cameraIndex].value<CameraMetaData*>(); cameraMetaData = _knownCameraList[cameraIndex].value<CameraMetaData*>();
...@@ -201,11 +201,12 @@ void CameraCalc::save(QJsonObject& json) const ...@@ -201,11 +201,12 @@ void CameraCalc::save(QJsonObject& json) const
} }
} }
bool CameraCalc::load(const QJsonObject& json, QString& errorString) bool CameraCalc::load(const QJsonObject& json, bool forPresets, bool cameraSpecInPreset, QString& errorString)
{ {
qDebug() << "CameraCalc::load" << forPresets << cameraSpecInPreset;
QJsonObject v1Json = json; QJsonObject v1Json = json;
if (!v1Json.contains(JsonHelper::jsonVersionKey)) { if (!json.contains(JsonHelper::jsonVersionKey)) {
// Version 0 file. Differences from Version 1 for conversion: // Version 0 file. Differences from Version 1 for conversion:
// JsonHelper::jsonVersionKey not stored // JsonHelper::jsonVersionKey not stored
// _jsonCameraSpecTypeKey stores CameraSpecType // _jsonCameraSpecTypeKey stores CameraSpecType
...@@ -231,18 +232,13 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString) ...@@ -231,18 +232,13 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
{ adjustedFootprintSideName, QJsonValue::Double, true }, { adjustedFootprintSideName, QJsonValue::Double, true },
{ adjustedFootprintFrontalName, QJsonValue::Double, true }, { adjustedFootprintFrontalName, QJsonValue::Double, true },
{ distanceToSurfaceName, QJsonValue::Double, true }, { distanceToSurfaceName, QJsonValue::Double, true },
{ distanceToSurfaceRelativeName, QJsonValue::Bool, true }, { distanceToSurfaceRelativeName, QJsonValue::Bool, true },
}; };
if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) { if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) {
return false; return false;
} }
_disableRecalc = true; _disableRecalc = !forPresets;
_cameraNameFact.setRawValue (v1Json[cameraNameName].toString());
_adjustedFootprintSideFact.setRawValue (v1Json[adjustedFootprintSideName].toDouble());
_adjustedFootprintFrontalFact.setRawValue (v1Json[adjustedFootprintFrontalName].toDouble());
_distanceToSurfaceFact.setRawValue (v1Json[distanceToSurfaceName].toDouble());
_distanceToSurfaceRelative = v1Json[distanceToSurfaceRelativeName].toBool(); _distanceToSurfaceRelative = v1Json[distanceToSurfaceRelativeName].toBool();
...@@ -259,13 +255,40 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString) ...@@ -259,13 +255,40 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
} }
_valueSetIsDistanceFact.setRawValue (v1Json[valueSetIsDistanceName].toBool()); _valueSetIsDistanceFact.setRawValue (v1Json[valueSetIsDistanceName].toBool());
_imageDensityFact.setRawValue (v1Json[imageDensityName].toDouble());
_frontalOverlapFact.setRawValue (v1Json[frontalOverlapName].toDouble()); _frontalOverlapFact.setRawValue (v1Json[frontalOverlapName].toDouble());
_sideOverlapFact.setRawValue (v1Json[sideOverlapName].toDouble()); _sideOverlapFact.setRawValue (v1Json[sideOverlapName].toDouble());
}
if (!CameraSpec::load(v1Json, errorString)) { if (forPresets) {
_disableRecalc = false; if (isManualCamera()) {
return false; _distanceToSurfaceFact.setRawValue(v1Json[distanceToSurfaceName].toDouble());
} else {
if (_valueSetIsDistanceFact.rawValue().toBool()) {
_distanceToSurfaceFact.setRawValue(v1Json[distanceToSurfaceName].toDouble());
} else {
_imageDensityFact.setRawValue(v1Json[imageDensityName].toDouble());
}
if (cameraSpecInPreset) {
_cameraNameFact.setRawValue(v1Json[cameraNameName].toString());
if (!CameraSpec::load(v1Json, errorString)) {
_disableRecalc = false;
return false;
}
}
}
} else {
_cameraNameFact.setRawValue (v1Json[cameraNameName].toString());
_adjustedFootprintSideFact.setRawValue (v1Json[adjustedFootprintSideName].toDouble());
_adjustedFootprintFrontalFact.setRawValue (v1Json[adjustedFootprintFrontalName].toDouble());
_distanceToSurfaceFact.setRawValue (v1Json[distanceToSurfaceName].toDouble());
if (!isManualCamera()) {
_imageDensityFact.setRawValue(v1Json[imageDensityName].toDouble());
if (!CameraSpec::load(v1Json, errorString)) {
_disableRecalc = false;
return false;
}
} }
} }
......
...@@ -70,7 +70,7 @@ public: ...@@ -70,7 +70,7 @@ public:
void setDistanceToSurfaceRelative (bool distanceToSurfaceRelative); void setDistanceToSurfaceRelative (bool distanceToSurfaceRelative);
void save(QJsonObject& json) const; void save(QJsonObject& json) const;
bool load(const QJsonObject& json, QString& errorString); bool load(const QJsonObject& json, bool forPresets, bool cameraSpecInPreset, QString& errorString);
static const char* cameraNameName; static const char* cameraNameName;
static const char* valueSetIsDistanceName; static const char* valueSetIsDistanceName;
......
...@@ -8,11 +8,21 @@ ...@@ -8,11 +8,21 @@
****************************************************************************/ ****************************************************************************/
#include "ComplexMissionItem.h" #include "ComplexMissionItem.h"
#include "QGCApplication.h"
#include <QSettings>
const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType"; const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
const char* ComplexMissionItem::_presetSettingsKey = "_presets";
const char* ComplexMissionItem::_presetNameKey = "complexItemPresetName";
const char* ComplexMissionItem::_saveCameraInPresetKey = "complexItemCameraSavedInPreset";
const char* ComplexMissionItem::_builtInPresetKey = "complexItemBuiltInPreset";
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent) ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: VisualMissionItem(vehicle, flyView, parent) : VisualMissionItem (vehicle, flyView, parent)
, _cameraInPreset (true)
, _builtInPreset (false)
{ {
} }
...@@ -21,5 +31,114 @@ const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem ...@@ -21,5 +31,114 @@ const ComplexMissionItem& ComplexMissionItem::operator=(const ComplexMissionItem
{ {
VisualMissionItem::operator=(other); VisualMissionItem::operator=(other);
_currentPreset = other._currentPreset;
_cameraInPreset = other._cameraInPreset;
_builtInPreset = other._builtInPreset;
return *this; return *this;
} }
QStringList ComplexMissionItem::presetNames(void)
{
QStringList names;
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
return settings.childKeys();
}
void ComplexMissionItem::loadPreset(const QString& name)
{
Q_UNUSED(name);
qgcApp()->showMessage(tr("This Pattern does not support Presets."));
}
void ComplexMissionItem::savePreset(const QString& name)
{
Q_UNUSED(name);
qgcApp()->showMessage(tr("This Pattern does not support Presets."));
}
void ComplexMissionItem::clearCurrentPreset(void)
{
_currentPreset.clear();
emit currentPresetChanged(_currentPreset);
}
void ComplexMissionItem::deleteCurrentPreset(void)
{
qDebug() << "deleteCurrentPreset" << _currentPreset;
if (!_currentPreset.isEmpty()) {
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
settings.remove(_currentPreset);
emit presetNamesChanged();
clearCurrentPreset();
}
}
void ComplexMissionItem::_savePresetJson(const QString& name, QJsonObject& presetObject)
{
presetObject[_presetNameKey] = name;
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
settings.setValue(name, QJsonDocument(presetObject).toBinaryData());
emit presetNamesChanged();
_currentPreset = name;
emit currentPresetChanged(name);
}
QJsonObject ComplexMissionItem::_loadPresetJson(const QString& name)
{
QSettings settings;
settings.beginGroup(presetsSettingsGroup());
settings.beginGroup(_presetSettingsKey);
return QJsonDocument::fromBinaryData(settings.value(name).toByteArray()).object();
}
void ComplexMissionItem::_saveItem(QJsonObject& saveObject)
{
qDebug() << "_saveItem" << _cameraInPreset;
saveObject[_presetNameKey] = _currentPreset;
saveObject[_saveCameraInPresetKey] = _cameraInPreset;
saveObject[_builtInPresetKey] = _builtInPreset;
}
void ComplexMissionItem::_loadItem(const QJsonObject& saveObject)
{
_currentPreset = saveObject[_presetNameKey].toString();
_cameraInPreset = saveObject[_saveCameraInPresetKey].toBool(false);
_builtInPreset = saveObject[_builtInPresetKey].toBool(false);
if (!presetNames().contains(_currentPreset)) {
_currentPreset.clear();
}
emit cameraInPresetChanged (_cameraInPreset);
emit currentPresetChanged (_currentPreset);
emit builtInPresetChanged (_builtInPreset);
}
void ComplexMissionItem::setCameraInPreset(bool cameraInPreset)
{
if (cameraInPreset != _cameraInPreset) {
_cameraInPreset = cameraInPreset;
emit cameraInPresetChanged(_cameraInPreset);
}
}
void ComplexMissionItem::setBuiltInPreset(bool builtInPreset)
{
if (builtInPreset != _builtInPreset) {
_builtInPreset = builtInPreset;
emit builtInPresetChanged(_builtInPreset);
}
}
...@@ -13,6 +13,8 @@ ...@@ -13,6 +13,8 @@
#include "VisualMissionItem.h" #include "VisualMissionItem.h"
#include "QGCGeo.h" #include "QGCGeo.h"
#include <QSettings>
class ComplexMissionItem : public VisualMissionItem class ComplexMissionItem : public VisualMissionItem
{ {
Q_OBJECT Q_OBJECT
...@@ -22,7 +24,12 @@ public: ...@@ -22,7 +24,12 @@ public:
const ComplexMissionItem& operator=(const ComplexMissionItem& other); const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged) Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged)
Q_PROPERTY(bool presetsSupported READ presetsSupported CONSTANT)
Q_PROPERTY(QStringList presetNames READ presetNames NOTIFY presetNamesChanged)
Q_PROPERTY(QString currentPreset READ currentPreset NOTIFY currentPresetChanged)
Q_PROPERTY(bool cameraInPreset READ cameraInPreset WRITE setCameraInPreset NOTIFY cameraInPresetChanged)
Q_PROPERTY(bool builtInPreset READ builtInPreset WRITE setBuiltInPreset NOTIFY builtInPresetChanged)
/// @return The distance covered the complex mission item in meters. /// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged /// Signals complexDistanceChanged
...@@ -35,12 +42,38 @@ public: ...@@ -35,12 +42,38 @@ public:
/// @return true: load success, false: load failed, errorString set /// @return true: load success, false: load failed, errorString set
virtual bool load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) = 0; virtual bool load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) = 0;
/// Loads the specified preset into the complex item.
/// @param name Preset name.
Q_INVOKABLE virtual void loadPreset(const QString& name);
/// Saves the current state of the complex item as the named preset.
/// @param name User visible name for preset. Will replace existing preset if already exists.
Q_INVOKABLE virtual void savePreset(const QString& name);
Q_INVOKABLE void clearCurrentPreset(void);
Q_INVOKABLE void deleteCurrentPreset(void);
/// Get the point of complex mission item furthest away from a coordinate /// Get the point of complex mission item furthest away from a coordinate
/// @param other QGeoCoordinate to which distance is calculated /// @param other QGeoCoordinate to which distance is calculated
/// @return the greatest distance from any point of the complex item to some coordinate /// @return the greatest distance from any point of the complex item to some coordinate
/// Signals greatestDistanceToChanged /// Signals greatestDistanceToChanged
virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0; virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0;
/// Returns the list of currently saved presets for this complex item type.
/// @param name User visible name for preset. Will replace existing preset if already exists.
virtual QStringList presetNames(void);
/// Returns the name of the settings group for presets.
/// Empty string signals no support for presets.
virtual QString presetsSettingsGroup(void) { return QString(); }
bool presetsSupported (void) { return !presetsSettingsGroup().isEmpty(); }
QString currentPreset (void) const { return _currentPreset; }
bool cameraInPreset (void) const { return _cameraInPreset; }
bool builtInPreset (void) const { return _builtInPreset; }
void setCameraInPreset (bool cameraInPreset);
void setBuiltInPreset (bool builtInPreset);
/// This mission item attribute specifies the type of the complex item. /// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey; static const char* jsonComplexItemTypeKey;
...@@ -48,6 +81,29 @@ signals: ...@@ -48,6 +81,29 @@ signals:
void complexDistanceChanged (void); void complexDistanceChanged (void);
void boundingCubeChanged (void); void boundingCubeChanged (void);
void greatestDistanceToChanged (void); void greatestDistanceToChanged (void);
void presetNamesChanged (void);
void currentPresetChanged (QString currentPreset);
void cameraInPresetChanged (bool cameraInPreset);
void builtInPresetChanged (bool builtInPreset);
protected:
void _saveItem (QJsonObject& saveObject);
void _loadItem (const QJsonObject& saveObject);
void _savePresetJson (const QString& name, QJsonObject& presetObject);
QJsonObject _loadPresetJson (const QString& name);
QMap<QString, FactMetaData*> _metaDataMap;
QString _currentPreset;
SettingsFact _saveCameraInPresetFact;
bool _cameraInPreset;
bool _builtInPreset;
static const char* _presetSettingsKey;
static const char* _presetNameKey;
static const char* _saveCameraInPresetKey;
static const char* _builtInPresetKey;
}; };
#endif #endif
...@@ -62,7 +62,7 @@ void CorridorScanComplexItem::save(QJsonArray& planItems) ...@@ -62,7 +62,7 @@ void CorridorScanComplexItem::save(QJsonArray& planItems)
{ {
QJsonObject saveObject; QJsonObject saveObject;
_save(saveObject); TransectStyleComplexItem::_save(saveObject);
saveObject[JsonHelper::jsonVersionKey] = 2; saveObject[JsonHelper::jsonVersionKey] = 2;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
...@@ -115,7 +115,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc ...@@ -115,7 +115,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc
setSequenceNumber(sequenceNumber); setSequenceNumber(sequenceNumber);
if (!_load(complexObject, errorString)) { if (!_load(complexObject, false /* forPresets */, errorString)) {
_ignoreRecalc = false; _ignoreRecalc = false;
return false; return false;
} }
......
...@@ -21,30 +21,51 @@ ...@@ -21,30 +21,51 @@
#include "QGCQGeoCoordinate.h" #include "QGCQGeoCoordinate.h"
#include "AppSettings.h" #include "AppSettings.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include <QJsonDocument> #include <QJsonDocument>
#include <QJsonArray> #include <QJsonArray>
QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog") QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog")
QMap<QString, FactMetaData*> GeoFenceController::_metaDataMap;
const char* GeoFenceController::_jsonFileTypeValue = "GeoFence"; const char* GeoFenceController::_jsonFileTypeValue = "GeoFence";
const char* GeoFenceController::_jsonBreachReturnKey = "breachReturn"; const char* GeoFenceController::_jsonBreachReturnKey = "breachReturn";
const char* GeoFenceController::_jsonPolygonsKey = "polygons"; const char* GeoFenceController::_jsonPolygonsKey = "polygons";
const char* GeoFenceController::_jsonCirclesKey = "circles"; const char* GeoFenceController::_jsonCirclesKey = "circles";
const char* GeoFenceController::_breachReturnAltitudeFactName = "Altitude";
const char* GeoFenceController::_px4ParamCircularFence = "GF_MAX_HOR_DIST"; const char* GeoFenceController::_px4ParamCircularFence = "GF_MAX_HOR_DIST";
GeoFenceController::GeoFenceController(PlanMasterController* masterController, QObject* parent) GeoFenceController::GeoFenceController(PlanMasterController* masterController, QObject* parent)
: PlanElementController (masterController, parent) : PlanElementController (masterController, parent)
, _geoFenceManager (_managerVehicle->geoFenceManager()) , _geoFenceManager (_managerVehicle->geoFenceManager())
, _dirty (false) , _dirty (false)
, _breachReturnAltitudeFact (0, _breachReturnAltitudeFactName, FactMetaData::valueTypeDouble)
, _breachReturnDefaultAltitude (qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble())
, _itemsRequested (false) , _itemsRequested (false)
, _px4ParamCircularFenceFact(NULL) , _px4ParamCircularFenceFact(nullptr)
{ {
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/BreachReturn.FactMetaData.json"), nullptr /* metaDataParent */);
}
_breachReturnAltitudeFact.setMetaData(_metaDataMap[_breachReturnAltitudeFactName]);
_breachReturnAltitudeFact.setRawValue(_breachReturnDefaultAltitude);
connect(&_polygons, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems); connect(&_polygons, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems);
connect(&_circles, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems); connect(&_circles, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems);
managerVehicleChanged(_managerVehicle); managerVehicleChanged(_managerVehicle);
connect(this, &GeoFenceController::breachReturnPointChanged, this, &GeoFenceController::_setDirty);
connect(&_breachReturnAltitudeFact, &Fact::rawValueChanged, this, &GeoFenceController::_setDirty);
connect(&_polygons, &QmlObjectListModel::dirtyChanged, this, &GeoFenceController::_setDirty);
connect(&_circles, &QmlObjectListModel::dirtyChanged, this, &GeoFenceController::_setDirty);
} }
GeoFenceController::~GeoFenceController() GeoFenceController::~GeoFenceController()
...@@ -74,26 +95,19 @@ void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturn ...@@ -74,26 +95,19 @@ void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturn
} }
} }
void GeoFenceController::_signalAll(void)
{
emit breachReturnPointChanged(breachReturnPoint());
emit dirtyChanged(dirty());
emit supportedChanged(supported());
}
void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle) void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle)
{ {
if (_managerVehicle) { if (_managerVehicle) {
_geoFenceManager->disconnect(this); _geoFenceManager->disconnect(this);
_managerVehicle->disconnect(this); _managerVehicle->disconnect(this);
_managerVehicle->parameterManager()->disconnect(this); _managerVehicle->parameterManager()->disconnect(this);
_managerVehicle = NULL; _managerVehicle = nullptr;
_geoFenceManager = NULL; _geoFenceManager = nullptr;
} }
_managerVehicle = managerVehicle; _managerVehicle = managerVehicle;
if (!_managerVehicle) { if (!_managerVehicle) {
qWarning() << "GeoFenceController::managerVehicleChanged managerVehicle=NULL"; qWarning() << "GeoFenceController::managerVehicleChanged managerVehicle=nullptr";
return; return;
} }
...@@ -109,7 +123,6 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle) ...@@ -109,7 +123,6 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle)
_parametersReady(); _parametersReady();
emit supportedChanged(supported()); emit supportedChanged(supported());
_signalAll();
} }
bool GeoFenceController::load(const QJsonObject& json, QString& errorString) bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
...@@ -128,6 +141,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) ...@@ -128,6 +141,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true }, { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
{ _jsonCirclesKey, QJsonValue::Array, true }, { _jsonCirclesKey, QJsonValue::Array, true },
{ _jsonPolygonsKey, QJsonValue::Array, true }, { _jsonPolygonsKey, QJsonValue::Array, true },
{ _jsonBreachReturnKey, QJsonValue::Array, false },
}; };
if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) { if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
return false; return false;
...@@ -139,7 +153,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) ...@@ -139,7 +153,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
} }
QJsonArray jsonPolygonArray = json[_jsonPolygonsKey].toArray(); QJsonArray jsonPolygonArray = json[_jsonPolygonsKey].toArray();
for (const QJsonValue& jsonPolygonValue: jsonPolygonArray) { for (const QJsonValue jsonPolygonValue: jsonPolygonArray) {
if (jsonPolygonValue.type() != QJsonValue::Object) { if (jsonPolygonValue.type() != QJsonValue::Object) {
errorString = tr("GeoFence polygon not stored as object"); errorString = tr("GeoFence polygon not stored as object");
return false; return false;
...@@ -153,7 +167,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) ...@@ -153,7 +167,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
} }
QJsonArray jsonCircleArray = json[_jsonCirclesKey].toArray(); QJsonArray jsonCircleArray = json[_jsonCirclesKey].toArray();
for (const QJsonValue& jsonCircleValue: jsonCircleArray) { for (const QJsonValue jsonCircleValue: jsonCircleArray) {
if (jsonCircleValue.type() != QJsonValue::Object) { if (jsonCircleValue.type() != QJsonValue::Object) {
errorString = tr("GeoFence circle not stored as object"); errorString = tr("GeoFence circle not stored as object");
return false; return false;
...@@ -166,8 +180,18 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) ...@@ -166,8 +180,18 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
_circles.append(fenceCircle); _circles.append(fenceCircle);
} }
if (json.contains(_jsonBreachReturnKey)) {
if (!JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], true /* altitudeRequred */, _breachReturnPoint, errorString)) {
return false;
}
_breachReturnAltitudeFact.setRawValue(_breachReturnPoint.altitude());
} else {
_breachReturnPoint = QGeoCoordinate();
_breachReturnAltitudeFact.setRawValue(_breachReturnDefaultAltitude);
}
emit breachReturnPointChanged(_breachReturnPoint);
setDirty(false); setDirty(false);
_signalAll();
return true; return true;
} }
...@@ -193,6 +217,14 @@ void GeoFenceController::save(QJsonObject& json) ...@@ -193,6 +217,14 @@ void GeoFenceController::save(QJsonObject& json)
jsonCircleArray.append(jsonCircle); jsonCircleArray.append(jsonCircle);
} }
json[_jsonCirclesKey] = jsonCircleArray; json[_jsonCirclesKey] = jsonCircleArray;
if (_breachReturnPoint.isValid()) {
QJsonValue jsonCoordinate;
_breachReturnPoint.setAltitude(_breachReturnAltitudeFact.rawValue().toDouble());
JsonHelper::saveGeoCoordinate(_breachReturnPoint, true /* writeAltitude */, jsonCoordinate);
json[_jsonBreachReturnKey] = jsonCoordinate;
}
} }
void GeoFenceController::removeAll(void) void GeoFenceController::removeAll(void)
...@@ -300,6 +332,11 @@ void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnP ...@@ -300,6 +332,11 @@ void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnP
{ {
_breachReturnPoint = breachReturnPoint; _breachReturnPoint = breachReturnPoint;
emit breachReturnPointChanged(_breachReturnPoint); emit breachReturnPointChanged(_breachReturnPoint);
if (_breachReturnPoint.isValid()) {
_breachReturnAltitudeFact.setRawValue(_breachReturnPoint.altitude());
} else {
_breachReturnAltitudeFact.setRawValue(_breachReturnDefaultAltitude);
}
} }
void GeoFenceController::_managerLoadComplete(void) void GeoFenceController::_managerLoadComplete(void)
...@@ -310,7 +347,6 @@ void GeoFenceController::_managerLoadComplete(void) ...@@ -310,7 +347,6 @@ void GeoFenceController::_managerLoadComplete(void)
_setReturnPointFromManager(_geoFenceManager->breachReturnPoint()); _setReturnPointFromManager(_geoFenceManager->breachReturnPoint());
_setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles()); _setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles());
setDirty(false); setDirty(false);
_signalAll();
emit loadComplete(); emit loadComplete();
} }
_itemsRequested = false; _itemsRequested = false;
...@@ -471,7 +507,7 @@ void GeoFenceController::_parametersReady(void) ...@@ -471,7 +507,7 @@ void GeoFenceController::_parametersReady(void)
{ {
if (_px4ParamCircularFenceFact) { if (_px4ParamCircularFenceFact) {
_px4ParamCircularFenceFact->disconnect(this); _px4ParamCircularFenceFact->disconnect(this);
_px4ParamCircularFenceFact = NULL; _px4ParamCircularFenceFact = nullptr;
} }
if (_managerVehicle->isOfflineEditingVehicle() || !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)) { if (_managerVehicle->isOfflineEditingVehicle() || !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)) {
......
...@@ -27,12 +27,13 @@ class GeoFenceController : public PlanElementController ...@@ -27,12 +27,13 @@ class GeoFenceController : public PlanElementController
Q_OBJECT Q_OBJECT
public: public:
GeoFenceController(PlanMasterController* masterController, QObject* parent = NULL); GeoFenceController(PlanMasterController* masterController, QObject* parent = nullptr);
~GeoFenceController(); ~GeoFenceController();
Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT) Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT)
Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT)
Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
Q_PROPERTY(Fact* breachReturnAltitude READ breachReturnAltitude CONSTANT)
// Hack to expose PX4 circular fence controlled by GF_MAX_HOR_DIST // Hack to expose PX4 circular fence controlled by GF_MAX_HOR_DIST
Q_PROPERTY(double paramCircularFence READ paramCircularFence NOTIFY paramCircularFenceChanged) Q_PROPERTY(double paramCircularFence READ paramCircularFence NOTIFY paramCircularFenceChanged)
...@@ -58,7 +59,8 @@ public: ...@@ -58,7 +59,8 @@ public:
/// Clears the interactive bit from all fence items /// Clears the interactive bit from all fence items
Q_INVOKABLE void clearAllInteractive(void); Q_INVOKABLE void clearAllInteractive(void);
double paramCircularFence(void); double paramCircularFence (void);
Fact* breachReturnAltitude(void) { return &_breachReturnAltitudeFact; }
// Overrides from PlanElementController // Overrides from PlanElementController
bool supported (void) const final; bool supported (void) const final;
...@@ -101,16 +103,19 @@ private slots: ...@@ -101,16 +103,19 @@ private slots:
private: private:
void _init(void); void _init(void);
void _signalAll(void);
GeoFenceManager* _geoFenceManager; GeoFenceManager* _geoFenceManager;
bool _dirty; bool _dirty;
QmlObjectListModel _polygons; QmlObjectListModel _polygons;
QmlObjectListModel _circles; QmlObjectListModel _circles;
QGeoCoordinate _breachReturnPoint; QGeoCoordinate _breachReturnPoint;
Fact _breachReturnAltitudeFact;
double _breachReturnDefaultAltitude;
bool _itemsRequested; bool _itemsRequested;
Fact* _px4ParamCircularFenceFact; Fact* _px4ParamCircularFenceFact;
static QMap<QString, FactMetaData*> _metaDataMap;
static const char* _px4ParamCircularFence; static const char* _px4ParamCircularFence;
static const int _jsonCurrentVersion = 2; static const int _jsonCurrentVersion = 2;
...@@ -119,6 +124,8 @@ private: ...@@ -119,6 +124,8 @@ private:
static const char* _jsonBreachReturnKey; static const char* _jsonBreachReturnKey;
static const char* _jsonPolygonsKey; static const char* _jsonPolygonsKey;
static const char* _jsonCirclesKey; static const char* _jsonCirclesKey;
static const char* _breachReturnAltitudeFactName;
}; };
#endif #endif
...@@ -51,8 +51,6 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, ...@@ -51,8 +51,6 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
QmlObjectListModel& polygons, QmlObjectListModel& polygons,
QmlObjectListModel& circles) QmlObjectListModel& circles)
{ {
Q_UNUSED(breachReturn);
QList<MissionItem*> fenceItems; QList<MissionItem*> fenceItems;
_sendPolygons.clear(); _sendPolygons.clear();
...@@ -64,6 +62,7 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, ...@@ -64,6 +62,7 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
for (int i=0; i<circles.count(); i++) { for (int i=0; i<circles.count(); i++) {
_sendCircles.append(*circles.value<QGCFenceCircle*>(i)); _sendCircles.append(*circles.value<QGCFenceCircle*>(i));
} }
_breachReturnPoint = breachReturn;
for (int i=0; i<_sendPolygons.count(); i++) { for (int i=0; i<_sendPolygons.count(); i++) {
const QGCFencePolygon& polygon = _sendPolygons[i]; const QGCFencePolygon& polygon = _sendPolygons[i];
...@@ -103,12 +102,30 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, ...@@ -103,12 +102,30 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
fenceItems.append(item); fenceItems.append(item);
} }
if (_breachReturnPoint.isValid()) {
MissionItem* item = new MissionItem(0,
MAV_CMD_NAV_FENCE_RETURN_POINT,
MAV_FRAME_GLOBAL_RELATIVE_ALT,
0, 0, 0, 0, // param 1-4 unused
breachReturn.latitude(),
breachReturn.longitude(),
breachReturn.altitude(),
false, // autocontinue
false, // isCurrentItem
this); // parent
fenceItems.append(item);
}
// Plan manager takes control of MissionItems, so no need to delete // Plan manager takes control of MissionItems, so no need to delete
_planManager.writeMissionItems(fenceItems); _planManager.writeMissionItems(fenceItems);
} }
void GeoFenceManager::removeAll(void) void GeoFenceManager::removeAll(void)
{ {
_polygons.clear();
_circles.clear();
_breachReturnPoint = QGeoCoordinate();
_planManager.removeAll(); _planManager.removeAll();
} }
...@@ -117,6 +134,7 @@ void GeoFenceManager::_sendComplete(bool error) ...@@ -117,6 +134,7 @@ void GeoFenceManager::_sendComplete(bool error)
if (error) { if (error) {
_polygons.clear(); _polygons.clear();
_circles.clear(); _circles.clear();
_breachReturnPoint = QGeoCoordinate();
} else { } else {
_polygons = _sendPolygons; _polygons = _sendPolygons;
_circles = _sendCircles; _circles = _sendCircles;
...@@ -174,6 +192,8 @@ void GeoFenceManager::_planManagerLoadComplete(bool removeAllRequested) ...@@ -174,6 +192,8 @@ void GeoFenceManager::_planManagerLoadComplete(bool removeAllRequested)
} }
QGCFenceCircle circle(QGeoCoordinate(item->param5(), item->param6()), item->param1(), command == MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION /* inclusion */); QGCFenceCircle circle(QGeoCoordinate(item->param5(), item->param6()), item->param1(), command == MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION /* inclusion */);
_circles.append(circle); _circles.append(circle);
} else if (command == MAV_CMD_NAV_FENCE_RETURN_POINT) {
_breachReturnPoint = QGeoCoordinate(item->param5(), item->param6(), item->param7());
} else { } else {
emit error(UnsupportedCommand, tr("GeoFence load: Unsupported command %1").arg(item->command())); emit error(UnsupportedCommand, tr("GeoFence load: Unsupported command %1").arg(item->command()));
break; break;
...@@ -183,6 +203,7 @@ void GeoFenceManager::_planManagerLoadComplete(bool removeAllRequested) ...@@ -183,6 +203,7 @@ void GeoFenceManager::_planManagerLoadComplete(bool removeAllRequested)
if (loadFailed) { if (loadFailed) {
_polygons.clear(); _polygons.clear();
_circles.clear(); _circles.clear();
_breachReturnPoint = QGeoCoordinate();
} }
emit loadComplete(); emit loadComplete();
......
...@@ -72,6 +72,7 @@ void RallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) ...@@ -72,6 +72,7 @@ void RallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints)
void RallyPointManager::removeAll(void) void RallyPointManager::removeAll(void)
{ {
_rgPoints.clear();
_planManager.removeAll(); _planManager.removeAll();
} }
......
...@@ -83,6 +83,9 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie ...@@ -83,6 +83,9 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie
connect(&_cameraCalc, &CameraCalc::isManualCameraChanged, this, &StructureScanComplexItem::_updateGimbalPitch); connect(&_cameraCalc, &CameraCalc::isManualCameraChanged, this, &StructureScanComplexItem::_updateGimbalPitch);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcScanDistance);
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcScanDistance);
_recalcLayerInfo(); _recalcLayerInfo();
if (!kmlOrShpFile.isEmpty()) { if (!kmlOrShpFile.isEmpty()) {
...@@ -93,14 +96,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie ...@@ -93,14 +96,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie
setDirty(false); setDirty(false);
} }
void StructureScanComplexItem::_setScanDistance(double scanDistance)
{
if (!qFuzzyCompare(_scanDistance, scanDistance)) {
_scanDistance = scanDistance;
emit complexDistanceChanged();
}
}
void StructureScanComplexItem::_setCameraShots(int cameraShots) void StructureScanComplexItem::_setCameraShots(int cameraShots)
{ {
if (_cameraShots != cameraShots) { if (_cameraShots != cameraShots) {
...@@ -218,7 +213,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen ...@@ -218,7 +213,7 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
setSequenceNumber(sequenceNumber); setSequenceNumber(sequenceNumber);
// Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles // Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles
if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) { if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), false /* forPresets */, false /* cameraSpecInPreset */, errorString)) {
return false; return false;
} }
...@@ -519,6 +514,7 @@ void StructureScanComplexItem::_rebuildFlightPolygon(void) ...@@ -519,6 +514,7 @@ void StructureScanComplexItem::_rebuildFlightPolygon(void)
} else { } else {
_entryVertex = savedEntryVertex; _entryVertex = savedEntryVertex;
} }
emit coordinateChanged(coordinate()); emit coordinateChanged(coordinate());
emit exitCoordinateChanged(exitCoordinate()); emit exitCoordinateChanged(exitCoordinate());
} }
...@@ -598,3 +594,26 @@ void StructureScanComplexItem::_signalTopBottomAltChanged(void) ...@@ -598,3 +594,26 @@ void StructureScanComplexItem::_signalTopBottomAltChanged(void)
emit topFlightAltChanged(); emit topFlightAltChanged();
emit bottomFlightAltChanged(); emit bottomFlightAltChanged();
} }
void StructureScanComplexItem::_recalcScanDistance()
{
double scanDistance = 0;
QList<QGeoCoordinate> vertices = _flightPolygon.coordinateList();
for (int i=0; i<vertices.count() - 1; i++) {
scanDistance += vertices[i].distanceTo(vertices[i+1]);
}
scanDistance *= _layersFact.rawValue().toInt();
double surfaceHeight = qMax(_structureHeightFact.rawValue().toDouble() - _scanBottomAltFact.rawValue().toDouble(), 0.0);
scanDistance += surfaceHeight;
if (!qFuzzyCompare(_scanDistance, scanDistance)) {
_scanDistance = scanDistance;
emit complexDistanceChanged();
}
qCDebug(StructureScanComplexItemLog) << "StructureScanComplexItem--_recalcScanDistance layers: "
<< _layersFact.rawValue().toInt() << " structure height: " << surfaceHeight
<< " scanDistance: " << _scanDistance;
}
...@@ -125,11 +125,11 @@ private slots: ...@@ -125,11 +125,11 @@ private slots:
void _recalcLayerInfo (void); void _recalcLayerInfo (void);
void _updateLastSequenceNumber (void); void _updateLastSequenceNumber (void);
void _updateGimbalPitch (void); void _updateGimbalPitch (void);
void _signalTopBottomAltChanged (void); void _signalTopBottomAltChanged (void);
void _recalcScanDistance (void);
private: private:
void _setExitCoordinate(const QGeoCoordinate& coordinate); void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _setScanDistance(double scanDistance);
void _setCameraShots(int cameraShots); void _setCameraShots(int cameraShots);
double _triggerDistance(void) const; double _triggerDistance(void) const;
......
...@@ -108,7 +108,21 @@ void SurveyComplexItem::save(QJsonArray& planItems) ...@@ -108,7 +108,21 @@ void SurveyComplexItem::save(QJsonArray& planItems)
{ {
QJsonObject saveObject; QJsonObject saveObject;
_save(saveObject); _saveWorker(saveObject);
planItems.append(saveObject);
}
void SurveyComplexItem::savePreset(const QString& name)
{
QJsonObject saveObject;
_saveWorker(saveObject);
_savePresetJson(name, saveObject);
}
void SurveyComplexItem::_saveWorker(QJsonObject& saveObject)
{
TransectStyleComplexItem::_save(saveObject);
saveObject[JsonHelper::jsonVersionKey] = 5; saveObject[JsonHelper::jsonVersionKey] = 5;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
...@@ -120,8 +134,15 @@ void SurveyComplexItem::save(QJsonArray& planItems) ...@@ -120,8 +134,15 @@ void SurveyComplexItem::save(QJsonArray& planItems)
// Polygon shape // Polygon shape
_surveyAreaPolygon.saveToJson(saveObject); _surveyAreaPolygon.saveToJson(saveObject);
}
planItems.append(saveObject); void SurveyComplexItem::loadPreset(const QString& name)
{
QString errorString;
QJsonObject presetObject = _loadPresetJson(name);
_loadV4V5(presetObject, 0, errorString, 5, true /* forPresets */);
_rebuildTransects();
} }
bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
...@@ -141,7 +162,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -141,7 +162,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
} }
if (version == 4 || version == 5) { if (version == 4 || version == 5) {
if (!_loadV4V5(complexObject, sequenceNumber, errorString, version)) { if (!_loadV4V5(complexObject, sequenceNumber, errorString, version, false /* forPresets */)) {
return false; return false;
} }
...@@ -171,7 +192,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -171,7 +192,7 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
return true; return true;
} }
bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version) bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version, bool forPresets)
{ {
QList<JsonHelper::KeyValidateInfo> keyInfoList = { QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
...@@ -197,16 +218,18 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence ...@@ -197,16 +218,18 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence
return false; return false;
} }
_ignoreRecalc = true; _ignoreRecalc = !forPresets;
setSequenceNumber(sequenceNumber); if (!forPresets) {
setSequenceNumber(sequenceNumber);
if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) { if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
_surveyAreaPolygon.clear(); _surveyAreaPolygon.clear();
return false; return false;
}
} }
if (!_load(complexObject, errorString)) { if (!TransectStyleComplexItem::_load(complexObject, forPresets, errorString)) {
_ignoreRecalc = false; _ignoreRecalc = false;
return false; return false;
} }
...@@ -214,7 +237,7 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence ...@@ -214,7 +237,7 @@ bool SurveyComplexItem::_loadV4V5(const QJsonObject& complexObject, int sequence
_gridAngleFact.setRawValue (complexObject[_jsonGridAngleKey].toDouble()); _gridAngleFact.setRawValue (complexObject[_jsonGridAngleKey].toDouble());
_flyAlternateTransectsFact.setRawValue (complexObject[_jsonFlyAlternateTransectsKey].toBool(false)); _flyAlternateTransectsFact.setRawValue (complexObject[_jsonFlyAlternateTransectsKey].toBool(false));
if(version == 5) { if (version == 5) {
_splitConcavePolygonsFact.setRawValue (complexObject[_jsonSplitConcavePolygonsKey].toBool(true)); _splitConcavePolygonsFact.setRawValue (complexObject[_jsonSplitConcavePolygonsKey].toBool(true));
} }
...@@ -282,7 +305,7 @@ bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNu ...@@ -282,7 +305,7 @@ bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNu
_turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble()); _turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble());
if (gridObject.contains(_jsonEntryPointKey)) { if (gridObject.contains(_jsonEntryPointKey)) {
_entryPoint = gridObject[_jsonEntryPointKey].toDouble(); _entryPoint = gridObject[_jsonEntryPointKey].toInt();
} else { } else {
_entryPoint = EntryLocationTopRight; _entryPoint = EntryLocationTopRight;
} }
......
...@@ -39,6 +39,9 @@ public: ...@@ -39,6 +39,9 @@ public:
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); }
QString presetsSettingsGroup(void) { return settingsGroup; }
void savePreset (const QString& name);
void loadPreset (const QString& name);
// Overrides from TransectStyleComplexItem // Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final; void save (QJsonArray& planItems) final;
...@@ -114,7 +117,8 @@ private: ...@@ -114,7 +117,8 @@ private:
double _turnaroundDistance(void) const; double _turnaroundDistance(void) const;
bool _hoverAndCaptureEnabled(void) const; bool _hoverAndCaptureEnabled(void) const;
bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString); bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
bool _loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version); bool _loadV4V5(const QJsonObject& complexObject, int sequenceNumber, QString& errorString, int version, bool forPresets);
void _saveWorker(QJsonObject& complexObject);
void _rebuildTransectsPhase1Worker(bool refly); void _rebuildTransectsPhase1Worker(bool refly);
void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly); void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly);
void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly); void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly);
......
...@@ -132,6 +132,8 @@ void TransectStyleComplexItem::setDirty(bool dirty) ...@@ -132,6 +132,8 @@ void TransectStyleComplexItem::setDirty(bool dirty)
void TransectStyleComplexItem::_save(QJsonObject& complexObject) void TransectStyleComplexItem::_save(QJsonObject& complexObject)
{ {
ComplexMissionItem::_saveItem(complexObject);
QJsonObject innerObject; QJsonObject innerObject;
innerObject[JsonHelper::jsonVersionKey] = 1; innerObject[JsonHelper::jsonVersionKey] = 1;
...@@ -183,8 +185,9 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber) ...@@ -183,8 +185,9 @@ void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber)
} }
} }
bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& errorString) bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forPresets, QString& errorString)
{ {
ComplexMissionItem::_loadItem(complexObject);
QList<JsonHelper::KeyValidateInfo> keyInfoList = { QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ _jsonTransectStyleComplexItemKey, QJsonValue::Object, true }, { _jsonTransectStyleComplexItemKey, QJsonValue::Object, true },
...@@ -211,8 +214,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& ...@@ -211,8 +214,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
{ hoverAndCaptureName, QJsonValue::Bool, true }, { hoverAndCaptureName, QJsonValue::Bool, true },
{ refly90DegreesName, QJsonValue::Bool, true }, { refly90DegreesName, QJsonValue::Bool, true },
{ _jsonCameraCalcKey, QJsonValue::Object, true }, { _jsonCameraCalcKey, QJsonValue::Object, true },
{ _jsonVisualTransectPointsKey, QJsonValue::Array, true }, { _jsonVisualTransectPointsKey, QJsonValue::Array, !forPresets },
{ _jsonItemsKey, QJsonValue::Array, true }, { _jsonItemsKey, QJsonValue::Array, !forPresets },
{ _jsonFollowTerrainKey, QJsonValue::Bool, true }, { _jsonFollowTerrainKey, QJsonValue::Bool, true },
{ _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation { _jsonCameraShotsKey, QJsonValue::Double, false }, // Not required since it was missing from initial implementation
}; };
...@@ -220,28 +223,30 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& ...@@ -220,28 +223,30 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
return false; return false;
} }
// Load visual transect points if (!forPresets) {
if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) { // Load visual transect points
return false; if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonVisualTransectPointsKey], false /* altitudeRequired */, _visualTransectPoints, errorString)) {
}
_coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
// Load generated mission items
_loadedMissionItemsParent = new QObject(this);
QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray();
for (const QJsonValue& missionItemJson: missionItemsJsonArray) {
MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent);
if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) {
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = NULL;
return false; return false;
} }
_loadedMissionItems.append(missionItem); _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
// Load generated mission items
_loadedMissionItemsParent = new QObject(this);
QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray();
for (const QJsonValue missionItemJson: missionItemsJsonArray) {
MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent);
if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) {
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = nullptr;
return false;
}
_loadedMissionItems.append(missionItem);
}
} }
// Load CameraCalc data // Load CameraCalc data
if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), errorString)) { if (!_cameraCalc.load(innerObject[_jsonCameraCalcKey].toObject(), forPresets, cameraInPreset(), errorString)) {
return false; return false;
} }
...@@ -435,7 +440,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) ...@@ -435,7 +440,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
// Let the signal fall on the floor // Let the signal fall on the floor
disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData); disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData);
#endif #endif
_terrainPolyPathQuery = NULL; _terrainPolyPathQuery = nullptr;
} }
// Append all transects into a single PolyPath query // Append all transects into a single PolyPath query
...@@ -479,7 +484,7 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te ...@@ -479,7 +484,7 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te
qWarning() << "TransectStyleComplexItem::_polyPathTerrainData _terrainPolyPathQuery != sender()"; qWarning() << "TransectStyleComplexItem::_polyPathTerrainData _terrainPolyPathQuery != sender()";
} }
disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData); disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData);
_terrainPolyPathQuery = NULL; _terrainPolyPathQuery = nullptr;
} }
bool TransectStyleComplexItem::readyForSave(void) const bool TransectStyleComplexItem::readyForSave(void) const
......
...@@ -141,7 +141,7 @@ protected: ...@@ -141,7 +141,7 @@ protected:
virtual void _recalcCameraShots (void) = 0; virtual void _recalcCameraShots (void) = 0;
void _save (QJsonObject& saveObject); void _save (QJsonObject& saveObject);
bool _load (const QJsonObject& complexObject, QString& errorString); bool _load (const QJsonObject& complexObject, bool forPresets, QString& errorString);
void _setExitCoordinate (const QGeoCoordinate& coordinate); void _setExitCoordinate (const QGeoCoordinate& coordinate);
void _setCameraShots (int cameraShots); void _setCameraShots (int cameraShots);
double _triggerDistance (void) const; double _triggerDistance (void) const;
......
...@@ -14,37 +14,53 @@ Column { ...@@ -14,37 +14,53 @@ Column {
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !usingPreset || !cameraSpecifiedInPreset
property var cameraCalc property var cameraCalc
property bool vehicleFlightIsFrontal: true property bool vehicleFlightIsFrontal: true
property string distanceToSurfaceLabel property string distanceToSurfaceLabel
property int distanceToSurfaceAltitudeMode: QGroundControl.AltitudeModeNone property int distanceToSurfaceAltitudeMode: QGroundControl.AltitudeModeNone
property string frontalDistanceLabel property string frontalDistanceLabel
property string sideDistanceLabel property string sideDistanceLabel
property bool usingPreset: false
property bool cameraSpecifiedInPreset: false
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
property int _cameraIndex: 1 property string _cameraName: cameraCalc.cameraName.value
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5 property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _cameraList: [ ] property var _cameraList: [ ]
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : [] property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
property bool _cameraComboFilled: false
readonly property int _gridTypeManual: 0 readonly property int _gridTypeManual: 0
readonly property int _gridTypeCustomCamera: 1 readonly property int _gridTypeCustomCamera: 1
readonly property int _gridTypeCamera: 2 readonly property int _gridTypeCamera: 2
Component.onCompleted: { Component.onCompleted: _fillCameraCombo()
on_CameraNameChanged: _updateSelectedCamera()
function _fillCameraCombo() {
_cameraComboFilled = true
_cameraList.push(cameraCalc.manualCameraName) _cameraList.push(cameraCalc.manualCameraName)
_cameraList.push(cameraCalc.customCameraName) _cameraList.push(cameraCalc.customCameraName)
for (var i=0; i<_vehicle.staticCameraList.length; i++) { for (var i=0; i<_vehicle.staticCameraList.length; i++) {
_cameraList.push(_vehicle.staticCameraList[i].name) _cameraList.push(_vehicle.staticCameraList[i].name)
} }
gridTypeCombo.model = _cameraList gridTypeCombo.model = _cameraList
var knownCameraIndex = gridTypeCombo.find(cameraCalc.cameraName.value) _updateSelectedCamera()
if (knownCameraIndex !== -1) { }
gridTypeCombo.currentIndex = knownCameraIndex
} else { function _updateSelectedCamera() {
console.log("Internal error: Known camera not found", cameraCalc.cameraName.value) if (_cameraComboFilled) {
gridTypeCombo.currentIndex = _gridTypeCustomCamera var knownCameraIndex = gridTypeCombo.find(_cameraName)
if (knownCameraIndex !== -1) {
gridTypeCombo.currentIndex = knownCameraIndex
} else {
console.log("Internal error: Known camera not found", _cameraName)
gridTypeCombo.currentIndex = _gridTypeCustomCamera
}
} }
} }
...@@ -179,6 +195,7 @@ Column { ...@@ -179,6 +195,7 @@ Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !usingPreset
Item { Layout.fillWidth: true } Item { Layout.fillWidth: true }
QGCLabel { QGCLabel {
Layout.preferredWidth: _root._fieldWidth Layout.preferredWidth: _root._fieldWidth
...@@ -194,6 +211,7 @@ Column { ...@@ -194,6 +211,7 @@ Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !usingPreset
QGCLabel { text: qsTr("Overlap"); Layout.fillWidth: true } QGCLabel { text: qsTr("Overlap"); Layout.fillWidth: true }
FactTextField { FactTextField {
Layout.preferredWidth: _root._fieldWidth Layout.preferredWidth: _root._fieldWidth
...@@ -210,6 +228,7 @@ Column { ...@@ -210,6 +228,7 @@ Column {
text: qsTr("Select one:") text: qsTr("Select one:")
Layout.preferredWidth: parent.width Layout.preferredWidth: parent.width
Layout.columnSpan: 2 Layout.columnSpan: 2
visible: !usingPreset
} }
GridLayout { GridLayout {
...@@ -218,6 +237,7 @@ Column { ...@@ -218,6 +237,7 @@ Column {
columnSpacing: _margin columnSpacing: _margin
rowSpacing: _margin rowSpacing: _margin
columns: 2 columns: 2
visible: !usingPreset
QGCRadioButton { QGCRadioButton {
id: fixedDistanceRadio id: fixedDistanceRadio
...@@ -248,33 +268,6 @@ Column { ...@@ -248,33 +268,6 @@ Column {
Layout.fillWidth: true Layout.fillWidth: true
} }
} }
// Calculated values
/*
Taking these out for now since they take up so much space. May come back at a later time.
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: frontalDistanceLabel }
FactTextField {
Layout.fillWidth: true
fact: cameraCalc.adjustedFootprintFrontal
enabled: false
}
QGCLabel { text: sideDistanceLabel }
FactTextField {
Layout.fillWidth: true
fact: cameraCalc.adjustedFootprintSide
enabled: false
}
} // GridLayout
*/
} // Column - Camera spec based ui } // Column - Camera spec based ui
// No camera spec ui // No camera spec ui
......
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2 import QtQuick.Layouts 1.2
import QtPositioning 5.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
...@@ -53,7 +54,7 @@ QGCFlickable { ...@@ -53,7 +54,7 @@ QGCFlickable {
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight / 2 spacing: _margin
QGCLabel { QGCLabel {
anchors.left: parent.left anchors.left: parent.left
...@@ -66,10 +67,10 @@ QGCFlickable { ...@@ -66,10 +67,10 @@ QGCFlickable {
} }
Column { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight / 2 spacing: _margin
visible: myGeoFenceController.supported visible: myGeoFenceController.supported
Repeater { Repeater {
model: myGeoFenceController.params model: myGeoFenceController.params
...@@ -114,9 +115,8 @@ QGCFlickable { ...@@ -114,9 +115,8 @@ QGCFlickable {
} }
QGCButton { QGCButton {
anchors.left: parent.left Layout.fillWidth: true
anchors.right: parent.right text: qsTr("Polygon Fence")
text: qsTr("Polygon Fence")
onClicked: { onClicked: {
var rect = Qt.rect(flightMap.centerViewport.x, flightMap.centerViewport.y, flightMap.centerViewport.width, flightMap.centerViewport.height) var rect = Qt.rect(flightMap.centerViewport.x, flightMap.centerViewport.y, flightMap.centerViewport.width, flightMap.centerViewport.height)
...@@ -127,9 +127,8 @@ QGCFlickable { ...@@ -127,9 +127,8 @@ QGCFlickable {
} }
QGCButton { QGCButton {
anchors.left: parent.left Layout.fillWidth: true
anchors.right: parent.right text: qsTr("Circular Fence")
text: qsTr("Circular Fence")
onClicked: { onClicked: {
var rect = Qt.rect(flightMap.centerViewport.x, flightMap.centerViewport.y, flightMap.centerViewport.width, flightMap.centerViewport.height) var rect = Qt.rect(flightMap.centerViewport.x, flightMap.centerViewport.y, flightMap.centerViewport.width, flightMap.centerViewport.height)
...@@ -150,11 +149,10 @@ QGCFlickable { ...@@ -150,11 +149,10 @@ QGCFlickable {
} }
GridLayout { GridLayout {
anchors.left: parent.left Layout.fillWidth: true
anchors.right: parent.right columns: 3
columns: 3 flow: GridLayout.TopToBottom
flow: GridLayout.TopToBottom visible: polygonSection.checked && myGeoFenceController.polygons.count > 0
visible: polygonSection.checked && myGeoFenceController.polygons.count > 0
QGCLabel { QGCLabel {
text: qsTr("Inclusion") text: qsTr("Inclusion")
...@@ -224,11 +222,11 @@ QGCFlickable { ...@@ -224,11 +222,11 @@ QGCFlickable {
} }
GridLayout { GridLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
columns: 4 columns: 4
flow: GridLayout.TopToBottom flow: GridLayout.TopToBottom
visible: polygonSection.checked && myGeoFenceController.circles.count > 0 visible: polygonSection.checked && myGeoFenceController.circles.count > 0
QGCLabel { QGCLabel {
text: qsTr("Inclusion") text: qsTr("Inclusion")
...@@ -302,6 +300,46 @@ QGCFlickable { ...@@ -302,6 +300,46 @@ QGCFlickable {
} }
} }
} // GridLayout } // GridLayout
SectionHeader {
id: breachReturnSection
text: qsTr("Breach Return Point")
}
QGCButton {
text: qsTr("Add Breach Return Point")
visible: breachReturnSection.visible && !myGeoFenceController.breachReturnPoint.isValid
anchors.left: parent.left
anchors.right: parent.right
onClicked: myGeoFenceController.breachReturnPoint = flightMap.center
}
QGCButton {
text: qsTr("Remove Breach Return Point")
visible: breachReturnSection.visible && myGeoFenceController.breachReturnPoint.isValid
anchors.left: parent.left
anchors.right: parent.right
onClicked: myGeoFenceController.breachReturnPoint = QtPositioning.coordinate()
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: breachReturnSection.visible && myGeoFenceController.breachReturnPoint.isValid
QGCLabel {
text: qsTr("Altitude")
}
AltitudeFactTextField {
fact: myGeoFenceController.breachReturnAltitude
altitudeMode: QGroundControl.AltitudeModeRelative
}
}
} }
} }
} }
......
...@@ -28,8 +28,8 @@ Item { ...@@ -28,8 +28,8 @@ Item {
property bool planView: false ///< true: visuals showing in plan view property bool planView: false ///< true: visuals showing in plan view
property var homePosition property var homePosition
//property var _breachReturnPointComponent property var _breachReturnPointComponent
//property var _mouseAreaComponent property var _breachReturnDragComponent
property var _paramCircleFenceComponent property var _paramCircleFenceComponent
property var _polygons: myGeoFenceController.polygons property var _polygons: myGeoFenceController.polygons
property var _circles: myGeoFenceController.circles property var _circles: myGeoFenceController.circles
...@@ -75,30 +75,19 @@ Item { ...@@ -75,30 +75,19 @@ Item {
} }
Component.onCompleted: { Component.onCompleted: {
//_breachReturnPointComponent = breachReturnPointComponent.createObject(map) _breachReturnPointComponent = breachReturnPointComponent.createObject(map)
//map.addMapItem(_breachReturnPointComponent) map.addMapItem(_breachReturnPointComponent)
//_mouseAreaComponent = mouseAreaComponent.createObject(map) _breachReturnDragComponent = breachReturnDragComponent.createObject(map, { "itemIndicator": _breachReturnPointComponent })
_paramCircleFenceComponent = paramCircleFenceComponent.createObject(map) _paramCircleFenceComponent = paramCircleFenceComponent.createObject(map)
map.addMapItem(_paramCircleFenceComponent) map.addMapItem(_paramCircleFenceComponent)
} }
Component.onDestruction: { Component.onDestruction: {
//_breachReturnPointComponent.destroy() _breachReturnPointComponent.destroy()
//_mouseAreaComponent.destroy() _breachReturnDragComponent.destroy()
_paramCircleFenceComponent.destroy() _paramCircleFenceComponent.destroy()
} }
// Mouse area to capture breach return point coordinate
Component {
id: mouseAreaComponent
MouseArea {
anchors.fill: map
visible: interactive
onClicked: myGeoFenceController.breachReturnPoint = map.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
}
}
Instantiator { Instantiator {
model: _polygons model: _polygons
...@@ -144,6 +133,19 @@ Item { ...@@ -144,6 +133,19 @@ Item {
} }
} }
Component {
id: breachReturnDragComponent
MissionItemIndicatorDrag {
mapControl: map
itemCoordinate: myGeoFenceController.breachReturnPoint
//visible: itemCoordinate.isValid
onItemCoordinateChanged: myGeoFenceController.breachReturnPoint = itemCoordinate
}
}
// Breach return point // Breach return point
Component { Component {
id: breachReturnPointComponent id: breachReturnPointComponent
...@@ -155,7 +157,8 @@ Item { ...@@ -155,7 +157,8 @@ Item {
coordinate: myGeoFenceController.breachReturnPoint coordinate: myGeoFenceController.breachReturnPoint
sourceItem: MissionItemIndexLabel { sourceItem: MissionItemIndexLabel {
label: "B" label: qsTr("B", "Breach Return Point item indicator")
checked: true
} }
} }
} }
......
This diff is collapsed.
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4 import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2 import QtQuick.Layouts 1.2
...@@ -29,6 +28,8 @@ Rectangle { ...@@ -29,6 +28,8 @@ Rectangle {
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5 property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property real _cameraMinTriggerInterval: missionItem.cameraCalc.minTriggerInterval.rawValue property real _cameraMinTriggerInterval: missionItem.cameraCalc.minTriggerInterval.rawValue
property string _currentPreset: missionItem.currentPreset
property bool _usingPreset: _currentPreset !== ""
function polygonCaptureStarted() { function polygonCaptureStarted() {
missionItem.clearPolygon() missionItem.clearPolygon()
...@@ -66,6 +67,97 @@ Rectangle { ...@@ -66,6 +67,97 @@ Rectangle {
visible: missionItem.cameraShots > 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots visible: missionItem.cameraShots > 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots
} }
QGCLabel {
text: qsTr("Presets")
}
QGCComboBox {
id: presetCombo
anchors.left: parent.left
anchors.right: parent.right
model: _presetList
property var _presetList: []
readonly property int _indexCustom: 0
readonly property int _indexCreate: 1
readonly property int _indexDelete: 2
readonly property int _indexLabel: 3
readonly property int _indexFirstPreset: 4
Component.onCompleted: _updateList()
onActivated: {
if (index == _indexCustom) {
missionItem.clearCurrentPreset()
} else if (index == _indexCreate) {
rootQgcView.showDialog(savePresetDialog, qsTr("Save Preset"), rootQgcView.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel)
} else if (index == _indexDelete) {
if (missionItem.builtInPreset) {
rootQgcView.showMessage(qsTr("Delete Preset"), qsTr("This preset cannot be deleted."), StandardButton.Ok)
} else {
missionItem.deleteCurrentPreset()
}
} else if (index >= _indexFirstPreset) {
missionItem.loadPreset(textAt(index))
} else {
_selectCurrentPreset()
}
}
Connections {
target: missionItem
onPresetNamesChanged: presetCombo._updateList()
onCurrentPresetChanged: presetCombo._selectCurrentPreset()
}
// There is some major strangeness going on with programatically changing the index of a combo box in this scenario.
// If you just set currentIndex directly it will just change back 1o -1 magically. Has something to do with resetting
// model on the fly I think. But not sure. To work around I delay the currentIndex changes to let things unwind.
Timer {
id: delayedIndexChangeTimer
interval: 10
property int newIndex
onTriggered: presetCombo.currentIndex = newIndex
}
function delayedIndexChange(index) {
delayedIndexChangeTimer.newIndex = index
delayedIndexChangeTimer.start()
}
function _updateList() {
_presetList = []
_presetList.push(qsTr("Custom (specify all settings)"))
_presetList.push(qsTr("Save Settings As Preset"))
_presetList.push(qsTr("Delete Current Preset"))
if (missionItem.presetNames.length !== 0) {
_presetList.push(qsTr("Presets:"))
}
for (var i=0; i<missionItem.presetNames.length; i++) {
_presetList.push(missionItem.presetNames[i])
}
model = _presetList
_selectCurrentPreset()
}
function _selectCurrentPreset() {
if (_usingPreset) {
var newIndex = find(_currentPreset)
if (newIndex !== -1) {
delayedIndexChange(newIndex)
return
}
}
delayedIndexChange(presetCombo._indexCustom)
}
}
CameraCalc { CameraCalc {
cameraCalc: missionItem.cameraCalc cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true vehicleFlightIsFrontal: true
...@@ -73,6 +165,8 @@ Rectangle { ...@@ -73,6 +165,8 @@ Rectangle {
distanceToSurfaceAltitudeMode: missionItem.followTerrain ? QGroundControl.AltitudeModeAboveTerrain : QGroundControl.AltitudeModeRelative distanceToSurfaceAltitudeMode: missionItem.followTerrain ? QGroundControl.AltitudeModeAboveTerrain : QGroundControl.AltitudeModeRelative
frontalDistanceLabel: qsTr("Trigger Dist") frontalDistanceLabel: qsTr("Trigger Dist")
sideDistanceLabel: qsTr("Spacing") sideDistanceLabel: qsTr("Spacing")
usingPreset: _usingPreset
cameraSpecifiedInPreset: missionItem.cameraInPreset
} }
SectionHeader { SectionHeader {
...@@ -109,23 +203,27 @@ Rectangle { ...@@ -109,23 +203,27 @@ Rectangle {
updateValueWhileDragging: true updateValueWhileDragging: true
} }
QGCLabel { text: qsTr("Turnaround dist") } QGCLabel {
text: qsTr("Turnaround dist")
visible: !_usingPreset
}
FactTextField { FactTextField {
fact: missionItem.turnAroundDistance fact: missionItem.turnAroundDistance
Layout.fillWidth: true Layout.fillWidth: true
visible: !_usingPreset
} }
} }
QGCButton {
text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint();
}
ColumnLayout { ColumnLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: transectsHeader.checked visible: transectsHeader.checked && !_usingPreset
QGCButton {
text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint();
}
/* /*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005 Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
...@@ -187,13 +285,15 @@ Rectangle { ...@@ -187,13 +285,15 @@ Rectangle {
id: terrainHeader id: terrainHeader
text: qsTr("Terrain") text: qsTr("Terrain")
checked: missionItem.followTerrain checked: missionItem.followTerrain
visible: !_usingPreset
} }
ColumnLayout { ColumnLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: terrainHeader.checked visible: terrainHeader.checked && !_usingPreset
QGCCheckBox { QGCCheckBox {
id: followsTerrainCheckBox id: followsTerrainCheckBox
...@@ -236,4 +336,45 @@ Rectangle { ...@@ -236,4 +336,45 @@ Rectangle {
TransectStyleComplexItemStats { } TransectStyleComplexItemStats { }
} // Column } // Column
Component {
id: savePresetDialog
QGCViewDialog {
function accept() {
if (presetNameField.text != "") {
missionItem.savePreset(presetNameField.text)
hideDialog()
}
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
Layout.fillWidth: true
text: qsTr("Save the current settings as a named preset.")
wrapMode: Text.WordWrap
}
QGCLabel {
text: qsTr("Preset Name")
}
QGCTextField {
id: presetNameField
Layout.fillWidth: true
text: _currentPreset
}
QGCCheckBox {
text: qsTr("Save Camera In Preset")
checked: missionItem.cameraInPreset
onClicked: missionItem.cameraInPreset = checked
}
}
}
}
} // Rectangle } // Rectangle
...@@ -2975,13 +2975,13 @@ QString Vehicle::gotoFlightMode() const ...@@ -2975,13 +2975,13 @@ QString Vehicle::gotoFlightMode() const
return _firmwarePlugin->gotoFlightMode(); return _firmwarePlugin->gotoFlightMode();
} }
void Vehicle::guidedModeRTL(void) void Vehicle::guidedModeRTL(bool smartRTL)
{ {
if (!guidedModeSupported()) { if (!guidedModeSupported()) {
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle); qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
return; return;
} }
_firmwarePlugin->guidedModeRTL(this); _firmwarePlugin->guidedModeRTL(this, smartRTL);
} }
void Vehicle::guidedModeLand(void) void Vehicle::guidedModeLand(void)
...@@ -3602,6 +3602,16 @@ QString Vehicle::rtlFlightMode(void) const ...@@ -3602,6 +3602,16 @@ QString Vehicle::rtlFlightMode(void) const
return _firmwarePlugin->rtlFlightMode(); return _firmwarePlugin->rtlFlightMode();
} }
QString Vehicle::smartRTLFlightMode(void) const
{
return _firmwarePlugin->smartRTLFlightMode();
}
bool Vehicle::supportsSmartRTL(void) const
{
return _firmwarePlugin->supportsSmartRTL();
}
QString Vehicle::landFlightMode(void) const QString Vehicle::landFlightMode(void) const
{ {
return _firmwarePlugin->landFlightMode(); return _firmwarePlugin->landFlightMode();
......
...@@ -600,6 +600,8 @@ public: ...@@ -600,6 +600,8 @@ public:
Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT) Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT) Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT)
Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT) Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
Q_PROPERTY(QString smartRTLFlightMode READ smartRTLFlightMode CONSTANT)
Q_PROPERTY(bool supportsSmartRTL READ supportsSmartRTL CONSTANT)
Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT) Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT)
Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT) Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged) Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
...@@ -698,7 +700,7 @@ public: ...@@ -698,7 +700,7 @@ public:
Q_INVOKABLE void disconnectInactiveVehicle(void); Q_INVOKABLE void disconnectInactiveVehicle(void);
/// Command vehicle to return to launch /// Command vehicle to return to launch
Q_INVOKABLE void guidedModeRTL(void); Q_INVOKABLE void guidedModeRTL(bool smartRTL);
/// Command vehicle to land at current location /// Command vehicle to land at current location
Q_INVOKABLE void guidedModeLand(void); Q_INVOKABLE void guidedModeLand(void);
...@@ -919,6 +921,8 @@ public: ...@@ -919,6 +921,8 @@ public:
QString missionFlightMode () const; QString missionFlightMode () const;
QString pauseFlightMode () const; QString pauseFlightMode () const;
QString rtlFlightMode () const; QString rtlFlightMode () const;
QString smartRTLFlightMode () const;
bool supportsSmartRTL () const;
QString landFlightMode () const; QString landFlightMode () const;
QString takeControlFlightMode () const; QString takeControlFlightMode () const;
double defaultCruiseSpeed () const { return _defaultCruiseSpeed; } double defaultCruiseSpeed () const { return _defaultCruiseSpeed; }
......
...@@ -145,6 +145,9 @@ public: ...@@ -145,6 +145,9 @@ public:
bool connect(void); bool connect(void);
bool disconnect(void); bool disconnect(void);
/// Don't even think of calling this method!
QSerialPort* _hackAccessToPort(void) { return _port; }
private slots: private slots:
/** /**
* @brief Write a number of bytes to the interface. * @brief Write a number of bytes to the interface.
......
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