From 6242b4bca2bd07aeb85334ed3d9e0718e58dd32a Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 15 Sep 2016 14:50:03 -0700 Subject: [PATCH] File persistence for GeoFence --- qgcresources.qrc | 1 + .../APM/CopterGeoFenceEditor.qml | 2 + .../APM/PlaneGeoFenceEditor.qml | 2 + src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml | 8 +- .../PX4/V1.4.OfflineEditing.params | 304 ++++++++++++++++++ src/FlightDisplay/FlightDisplayViewMap.qml | 4 +- src/FlightMap/FlightMap.qml | 1 + src/JsonHelper.cc | 26 +- src/JsonHelper.h | 12 +- src/MissionEditor/GeoFenceEditor.qml | 10 - src/MissionEditor/MissionEditor.qml | 45 ++- src/MissionEditor/QGCMapPolygonControls.qml | 8 +- src/MissionManager/GeoFenceController.cc | 206 +++++++++++- src/MissionManager/GeoFenceController.h | 13 +- src/MissionManager/MissionController.cc | 16 +- src/MissionManager/MissionController.h | 2 - src/MissionManager/QGCMapPolygon.cc | 57 ++++ src/MissionManager/QGCMapPolygon.h | 13 + src/MissionManager/SurveyMissionItem.cc | 9 +- src/MissionManager/SurveyMissionItem.h | 1 - src/QGCApplication.cc | 3 +- src/QGCApplication.h | 1 + 22 files changed, 678 insertions(+), 66 deletions(-) create mode 100644 src/FirmwarePlugin/PX4/V1.4.OfflineEditing.params diff --git a/qgcresources.qrc b/qgcresources.qrc index 95e62681c..959f2456e 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -282,6 +282,7 @@ src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml + src/FirmwarePlugin/PX4/V1.4.OfflineEditing.params resources/opengl/buglist.json diff --git a/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml b/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml index 120221ee3..f9bc0871a 100644 --- a/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml +++ b/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml @@ -78,5 +78,7 @@ Column { polygon: geoFenceController.polygon sectionLabel: qsTr("Fence Polygon:") visible: geoFenceController.polygonSupported + + onPolygonEditCompleted: geoFenceController.sendToVehicle() } } diff --git a/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml b/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml index 88ed21e36..76ce0b994 100644 --- a/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml +++ b/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml @@ -220,5 +220,7 @@ Column { flightMap: editorMap polygon: geoFenceController.polygon sectionLabel: qsTr("Fence Polygon:") + + onPolygonEditCompleted: geoFenceController.sendToVehicle() } } diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml b/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml index 060bc4eaf..441f26a48 100644 --- a/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml +++ b/src/FirmwarePlugin/PX4/PX4GeoFenceEditor.qml @@ -22,7 +22,7 @@ Column { property Fact _fenceAction: factController.getParameterFact(-1, "GF_ACTION") property Fact _fenceRadius: factController.getParameterFact(-1, "GF_MAX_HOR_DIST") - property Fact _fenceAlt: factController.getParameterFact(-1, "GF_MAX_VER_DIST") + property Fact _fenceMaxAlt: factController.getParameterFact(-1, "GF_MAX_VER_DIST") FactPanelController { id: factController @@ -80,8 +80,8 @@ Column { QGCCheckBox { id: maxAltFenceCheckBox text: qsTr("Maximum altitude fence") - checked: _fenceAlt.value > 0 - onClicked: _fenceAlt.value = checked ? 100 : 0 + checked: _fenceMaxAlt.value > 0 + onClicked: _fenceMaxAlt.value = checked ? 100 : 0 } Row { @@ -97,7 +97,7 @@ Column { FactTextField { id: fenceAltMaxField showUnits: true - fact: _fenceAlt + fact: _fenceMaxAlt enabled: maxAltFenceCheckBox.checked width: _editFieldWidth } diff --git a/src/FirmwarePlugin/PX4/V1.4.OfflineEditing.params b/src/FirmwarePlugin/PX4/V1.4.OfflineEditing.params new file mode 100644 index 000000000..4e4a9f0d5 --- /dev/null +++ b/src/FirmwarePlugin/PX4/V1.4.OfflineEditing.params @@ -0,0 +1,304 @@ +# Onboard parameters for vehicle 1 +# +# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT) +1 1 ATT_VIBE_THRESH 0.200000002980232239 9 +1 1 BAT_A_PER_V 15.391030311584472656 9 +1 1 BAT_CAPACITY -1.000000000000000000 9 +1 1 BAT_CNT_V_CURR 0.000805664050858468 9 +1 1 BAT_CNT_V_VOLT 0.000805664050858468 9 +1 1 BAT_CRIT_THR 0.070000000298023224 9 +1 1 BAT_LOW_THR 0.150000005960464478 9 +1 1 BAT_N_CELLS 3 6 +1 1 BAT_SOURCE 0 6 +1 1 BAT_V_CHARGED 4.050000190734863281 9 +1 1 BAT_V_DIV 10.177939414978027344 9 +1 1 BAT_V_EMPTY 3.400000095367431641 9 +1 1 BAT_V_LOAD_DROP 0.300000011920928955 9 +1 1 BAT_V_OFFS_CURR 0.000000000000000000 9 +1 1 BAT_V_SCALE_IO 10000 6 +1 1 CAL_ACC0_ID 0 6 +1 1 CAL_ACC1_ID 0 6 +1 1 CAL_ACC2_ID 0 6 +1 1 CAL_ACC_PRIME 0 6 +1 1 CAL_BARO_PRIME 0 6 +1 1 CAL_GYRO0_ID 0 6 +1 1 CAL_GYRO1_ID 0 6 +1 1 CAL_GYRO2_ID 0 6 +1 1 CAL_GYRO_PRIME 0 6 +1 1 CAL_MAG0_ID 0 6 +1 1 CAL_MAG0_ROT -1 6 +1 1 CAL_MAG1_ID 0 6 +1 1 CAL_MAG1_ROT -1 6 +1 1 CAL_MAG2_ID 0 6 +1 1 CAL_MAG2_ROT -1 6 +1 1 CAL_MAG_PRIME 0 6 +1 1 CAL_MAG_SIDES 63 6 +1 1 CBRK_AIRSPD_CHK 0 6 +1 1 CBRK_BUZZER 0 6 +1 1 CBRK_ENGINEFAIL 284953 6 +1 1 CBRK_FLIGHTTERM 121212 6 +1 1 CBRK_GPSFAIL 0 6 +1 1 CBRK_IO_SAFETY 0 6 +1 1 CBRK_SUPPLY_CHK 0 6 +1 1 CBRK_USB_CHK 0 6 +1 1 COM_ARM_WO_GPS 1 6 +1 1 COM_AUTOS_PAR 1 6 +1 1 COM_DISARM_LAND 0 6 +1 1 COM_DL_LOSS_T 10 6 +1 1 COM_DL_REG_T 0 6 +1 1 COM_EF_C2T 5.000000000000000000 9 +1 1 COM_EF_THROT 0.500000000000000000 9 +1 1 COM_EF_TIME 10.000000000000000000 9 +1 1 COM_FLTMODE1 -1 6 +1 1 COM_FLTMODE2 -1 6 +1 1 COM_FLTMODE3 -1 6 +1 1 COM_FLTMODE4 -1 6 +1 1 COM_FLTMODE5 -1 6 +1 1 COM_FLTMODE6 -1 6 +1 1 COM_HOME_H_T 5.000000000000000000 9 +1 1 COM_HOME_V_T 10.000000000000000000 9 +1 1 COM_LOW_BAT_ACT 0 6 +1 1 COM_OBL_ACT 0 6 +1 1 COM_OBL_RC_ACT 0 6 +1 1 COM_OF_LOSS_T 0.000000000000000000 9 +1 1 COM_RC_ARM_HYST 1000 6 +1 1 COM_RC_IN_MODE 0 6 +1 1 COM_RC_LOSS_T 0.500000000000000000 9 +1 1 EKF2_REC_RPL 0 6 +1 1 FW_AIRSPD_TRIM 15.000000000000000000 9 +1 1 FW_MAN_P_SC 1.000000000000000000 9 +1 1 FW_MAN_R_SC 1.000000000000000000 9 +1 1 FW_MAN_Y_SC 1.000000000000000000 9 +1 1 FW_THR_CRUISE 0.600000023841857910 9 +1 1 GF_ACTION 1 6 +1 1 GF_ALTMODE 0 6 +1 1 GF_COUNT -1 6 +1 1 GF_MAX_HOR_DIST 0 6 +1 1 GF_MAX_VER_DIST 0 6 +1 1 GF_SOURCE 0 6 +1 1 GPS_DUMP_COMM 0 6 +1 1 INAV_LIDAR_ERR 0.200000002980232239 9 +1 1 MAV_BROADCAST 0 6 +1 1 MAV_COMP_ID 1 6 +1 1 MAV_FWDEXTSP 1 6 +1 1 MAV_PROTO_VER 1 6 +1 1 MAV_RADIO_ID 0 6 +1 1 MAV_SYS_ID 1 6 +1 1 MAV_TEST_PAR 1 6 +1 1 MAV_TYPE 2 6 +1 1 MAV_USEHILGPS 0 6 +1 1 MC_YAWRAUTO_MAX 45.000000000000000000 9 +1 1 MIS_ALTMODE 1 6 +1 1 MIS_DIST_1WP 900.000000000000000000 9 +1 1 MIS_LTRMIN_ALT 1.200000047683715820 9 +1 1 MIS_ONBOARD_EN 1 6 +1 1 MIS_TAKEOFF_ALT 10.000000000000000000 9 +1 1 MIS_YAWMODE 1 6 +1 1 MIS_YAW_ERR 12.000000000000000000 9 +1 1 MIS_YAW_TMT -1.000000000000000000 9 +1 1 MPC_XY_CRUISE 5.000000000000000000 9 +1 1 NAV_ACC_RAD 10.000000000000000000 9 +1 1 NAV_AH_ALT 600.000000000000000000 9 +1 1 NAV_AH_LAT -265847810 6 +1 1 NAV_AH_LON 1518423250 6 +1 1 NAV_DLL_ACT 0 6 +1 1 NAV_DLL_AH_T 120.000000000000000000 9 +1 1 NAV_DLL_CHSK 0 6 +1 1 NAV_DLL_CH_ALT 600.000000000000000000 9 +1 1 NAV_DLL_CH_LAT -266072120 6 +1 1 NAV_DLL_CH_LON 1518453890 6 +1 1 NAV_DLL_CH_T 120.000000000000000000 9 +1 1 NAV_DLL_N 2 6 +1 1 NAV_FT_DST 8.000000000000000000 9 +1 1 NAV_FT_FS 1 6 +1 1 NAV_FT_RS 0.500000000000000000 9 +1 1 NAV_FW_ALT_RAD 10.000000000000000000 9 +1 1 NAV_GPSF_LT 30.000000000000000000 9 +1 1 NAV_GPSF_P 0.000000000000000000 9 +1 1 NAV_GPSF_R 15.000000000000000000 9 +1 1 NAV_GPSF_TR 0.699999988079071045 9 +1 1 NAV_LOITER_RAD 50.000000000000000000 9 +1 1 NAV_MC_ALT_RAD 3.000000000000000000 9 +1 1 NAV_MIN_FT_HT 8.000000000000000000 9 +1 1 NAV_RCL_ACT 2 6 +1 1 NAV_RCL_LT 120.000000000000000000 9 +1 1 PWM_AUX_DISARMED 1000 6 +1 1 PWM_AUX_MAX 2000 6 +1 1 PWM_AUX_MIN 1000 6 +1 1 PWM_DISARMED 0 6 +1 1 PWM_MAIN_REV1 0 6 +1 1 PWM_MAIN_REV2 0 6 +1 1 PWM_MAIN_REV3 0 6 +1 1 PWM_MAIN_REV4 0 6 +1 1 PWM_MAIN_REV5 0 6 +1 1 PWM_MAIN_REV6 0 6 +1 1 PWM_MAIN_REV7 0 6 +1 1 PWM_MAIN_REV8 0 6 +1 1 PWM_MAX 2000 6 +1 1 PWM_MIN 1000 6 +1 1 PWM_SBUS_MODE 0 6 +1 1 RC10_DZ 0.000000000000000000 9 +1 1 RC10_MAX 2000.000000000000000000 9 +1 1 RC10_MIN 1000.000000000000000000 9 +1 1 RC10_REV 1.000000000000000000 9 +1 1 RC10_TRIM 1500.000000000000000000 9 +1 1 RC11_DZ 0.000000000000000000 9 +1 1 RC11_MAX 2000.000000000000000000 9 +1 1 RC11_MIN 1000.000000000000000000 9 +1 1 RC11_REV 1.000000000000000000 9 +1 1 RC11_TRIM 1500.000000000000000000 9 +1 1 RC12_DZ 0.000000000000000000 9 +1 1 RC12_MAX 2000.000000000000000000 9 +1 1 RC12_MIN 1000.000000000000000000 9 +1 1 RC12_REV 1.000000000000000000 9 +1 1 RC12_TRIM 1500.000000000000000000 9 +1 1 RC13_DZ 0.000000000000000000 9 +1 1 RC13_MAX 2000.000000000000000000 9 +1 1 RC13_MIN 1000.000000000000000000 9 +1 1 RC13_REV 1.000000000000000000 9 +1 1 RC13_TRIM 1500.000000000000000000 9 +1 1 RC14_DZ 0.000000000000000000 9 +1 1 RC14_MAX 2000.000000000000000000 9 +1 1 RC14_MIN 1000.000000000000000000 9 +1 1 RC14_REV 1.000000000000000000 9 +1 1 RC14_TRIM 1500.000000000000000000 9 +1 1 RC15_DZ 0.000000000000000000 9 +1 1 RC15_MAX 2000.000000000000000000 9 +1 1 RC15_MIN 1000.000000000000000000 9 +1 1 RC15_REV 1.000000000000000000 9 +1 1 RC15_TRIM 1500.000000000000000000 9 +1 1 RC16_DZ 0.000000000000000000 9 +1 1 RC16_MAX 2000.000000000000000000 9 +1 1 RC16_MIN 1000.000000000000000000 9 +1 1 RC16_REV 1.000000000000000000 9 +1 1 RC16_TRIM 1500.000000000000000000 9 +1 1 RC17_DZ 0.000000000000000000 9 +1 1 RC17_MAX 2000.000000000000000000 9 +1 1 RC17_MIN 1000.000000000000000000 9 +1 1 RC17_REV 1.000000000000000000 9 +1 1 RC17_TRIM 1500.000000000000000000 9 +1 1 RC18_DZ 0.000000000000000000 9 +1 1 RC18_MAX 2000.000000000000000000 9 +1 1 RC18_MIN 1000.000000000000000000 9 +1 1 RC18_REV 1.000000000000000000 9 +1 1 RC18_TRIM 1500.000000000000000000 9 +1 1 RC1_DZ 10.000000000000000000 9 +1 1 RC1_MAX 2000.000000000000000000 9 +1 1 RC1_MIN 1000.000000000000000000 9 +1 1 RC1_REV 1.000000000000000000 9 +1 1 RC1_TRIM 1500.000000000000000000 9 +1 1 RC2_DZ 10.000000000000000000 9 +1 1 RC2_MAX 2000.000000000000000000 9 +1 1 RC2_MIN 1000.000000000000000000 9 +1 1 RC2_REV 1.000000000000000000 9 +1 1 RC2_TRIM 1500.000000000000000000 9 +1 1 RC3_DZ 10.000000000000000000 9 +1 1 RC3_MAX 2000.000000000000000000 9 +1 1 RC3_MIN 1000.000000000000000000 9 +1 1 RC3_REV 1.000000000000000000 9 +1 1 RC3_TRIM 1500.000000000000000000 9 +1 1 RC4_DZ 10.000000000000000000 9 +1 1 RC4_MAX 2000.000000000000000000 9 +1 1 RC4_MIN 1000.000000000000000000 9 +1 1 RC4_REV 1.000000000000000000 9 +1 1 RC4_TRIM 1500.000000000000000000 9 +1 1 RC5_DZ 10.000000000000000000 9 +1 1 RC5_MAX 2000.000000000000000000 9 +1 1 RC5_MIN 1000.000000000000000000 9 +1 1 RC5_REV 1.000000000000000000 9 +1 1 RC5_TRIM 1500.000000000000000000 9 +1 1 RC6_DZ 10.000000000000000000 9 +1 1 RC6_MAX 2000.000000000000000000 9 +1 1 RC6_MIN 1000.000000000000000000 9 +1 1 RC6_REV 1.000000000000000000 9 +1 1 RC6_TRIM 1500.000000000000000000 9 +1 1 RC7_DZ 10.000000000000000000 9 +1 1 RC7_MAX 2000.000000000000000000 9 +1 1 RC7_MIN 1000.000000000000000000 9 +1 1 RC7_REV 1.000000000000000000 9 +1 1 RC7_TRIM 1500.000000000000000000 9 +1 1 RC8_DZ 10.000000000000000000 9 +1 1 RC8_MAX 2000.000000000000000000 9 +1 1 RC8_MIN 1000.000000000000000000 9 +1 1 RC8_REV 1.000000000000000000 9 +1 1 RC8_TRIM 1500.000000000000000000 9 +1 1 RC9_DZ 0.000000000000000000 9 +1 1 RC9_MAX 2000.000000000000000000 9 +1 1 RC9_MIN 1000.000000000000000000 9 +1 1 RC9_REV 1.000000000000000000 9 +1 1 RC9_TRIM 1500.000000000000000000 9 +1 1 RC_ACRO_TH 0.500000000000000000 9 +1 1 RC_ASSIST_TH 0.250000000000000000 9 +1 1 RC_AUTO_TH 0.750000000000000000 9 +1 1 RC_CHAN_CNT 0 6 +1 1 RC_DSM_BIND -1 6 +1 1 RC_FAILS_THR 0 6 +1 1 RC_KILLSWITCH_TH 0.250000000000000000 9 +1 1 RC_LOITER_TH 0.500000000000000000 9 +1 1 RC_MAP_ACRO_SW 0 6 +1 1 RC_MAP_AUX1 0 6 +1 1 RC_MAP_AUX2 0 6 +1 1 RC_MAP_AUX3 0 6 +1 1 RC_MAP_AUX4 0 6 +1 1 RC_MAP_AUX5 0 6 +1 1 RC_MAP_FAILSAFE 0 6 +1 1 RC_MAP_FLAPS 0 6 +1 1 RC_MAP_FLTMODE 0 6 +1 1 RC_MAP_KILL_SW 0 6 +1 1 RC_MAP_LOITER_SW 0 6 +1 1 RC_MAP_MODE_SW 0 6 +1 1 RC_MAP_OFFB_SW 0 6 +1 1 RC_MAP_PARAM1 0 6 +1 1 RC_MAP_PARAM2 0 6 +1 1 RC_MAP_PARAM3 0 6 +1 1 RC_MAP_PITCH 0 6 +1 1 RC_MAP_POSCTL_SW 0 6 +1 1 RC_MAP_RATT_SW 0 6 +1 1 RC_MAP_RETURN_SW 0 6 +1 1 RC_MAP_ROLL 0 6 +1 1 RC_MAP_THROTTLE 0 6 +1 1 RC_MAP_TRANS_SW 0 6 +1 1 RC_MAP_YAW 0 6 +1 1 RC_OFFB_TH 0.500000000000000000 9 +1 1 RC_POSCTL_TH 0.500000000000000000 9 +1 1 RC_RATT_TH 0.500000000000000000 9 +1 1 RC_RETURN_TH 0.500000000000000000 9 +1 1 RC_RSSI_PWM_CHAN 0 6 +1 1 RC_RSSI_PWM_MAX 1000 6 +1 1 RC_RSSI_PWM_MIN 2000 6 +1 1 RC_TH_USER 1 6 +1 1 RC_TRANS_TH 0.250000000000000000 9 +1 1 RTL_DESCEND_ALT 30.000000000000000000 9 +1 1 RTL_LAND_DELAY -1.000000000000000000 9 +1 1 RTL_MIN_DIST 5.000000000000000000 9 +1 1 RTL_RETURN_ALT 60.000000000000000000 9 +1 1 SDLOG_EXT -1 6 +1 1 SDLOG_GPSTIME 1 6 +1 1 SDLOG_PRIO_BOOST 2 6 +1 1 SDLOG_RATE -1 6 +1 1 SENS_BARO_QNH 1013.250000000000000000 9 +1 1 SENS_BOARD_ROT 0 6 +1 1 SENS_BOARD_X_OFF 0.000000000000000000 9 +1 1 SENS_BOARD_Y_OFF 0.000000000000000000 9 +1 1 SENS_BOARD_Z_OFF 0.000000000000000000 9 +1 1 SENS_DPRES_ANSC 0.000000000000000000 9 +1 1 SENS_DPRES_OFF 0.000000000000000000 9 +1 1 SENS_EN_LL40LS 0 6 +1 1 SENS_EN_MB12XX 0 6 +1 1 SENS_EN_SF0X 0 6 +1 1 SYS_AUTOCONFIG 0 6 +1 1 SYS_AUTOSTART 0 6 +1 1 SYS_COMPANION 157600 6 +1 1 SYS_LOGGER 0 6 +1 1 SYS_MC_EST_GROUP 1 6 +1 1 SYS_PARAM_VER 1 6 +1 1 SYS_RESTART_TYPE 0 6 +1 1 SYS_USE_IO 1 6 +1 1 TRIG_MODE 0 6 +1 1 TRIM_PITCH 0.000000000000000000 9 +1 1 TRIM_ROLL 0.000000000000000000 9 +1 1 TRIM_YAW 0.000000000000000000 9 +1 1 UAVCAN_ENABLE 0 6 +1 1 VT_NAV_FORCE_VT 1 6 +1 1 VT_WV_LND_EN 0 6 +1 1 VT_WV_LTR_EN 0 6 diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index bcaea7788..e1108d57c 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -87,7 +87,7 @@ FlightMap { coordinate: object.coordinate isSatellite: flightMap.isSatelliteMap size: _mainIsMap ? ScreenTools.defaultFontPixelHeight * 5 : ScreenTools.defaultFontPixelHeight * 2 - z: QGroundControl.zOrderMapItems + z: QGroundControl.zOrderMapItems - 1 } } @@ -114,6 +114,7 @@ FlightMap { border.width: 3 center: missionController.plannedHomePosition radius: geoFenceController.circleSupported ? geoFenceController.circleRadius : 0 + z: QGroundControl.zOrderMapItems } // GeoFence breach return point @@ -122,6 +123,7 @@ FlightMap { coordinate: geoFenceController.breachReturnPoint visible: geoFenceController.breachReturnSupported sourceItem: MissionItemIndexLabel { label: "F" } + z: QGroundControl.zOrderMapItems } // GoTo here waypoint diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 340f2bf07..24a8458a8 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -119,6 +119,7 @@ Map { onMapTypeChanged: updateActiveMapType() } + /// Ground Station location MapQuickItem { anchorPoint.x: sourceItem.width / 2 anchorPoint.y: sourceItem.height / 2 diff --git a/src/JsonHelper.cc b/src/JsonHelper.cc index fbb413138..25ae0f5b6 100644 --- a/src/JsonHelper.cc +++ b/src/JsonHelper.cc @@ -11,9 +11,14 @@ #include "JsonHelper.h" #include +#include -const char* JsonHelper::_enumStringsJsonKey = "enumStrings"; -const char* JsonHelper::_enumValuesJsonKey = "enumValues"; +const char* JsonHelper::_enumStringsJsonKey = "enumStrings"; +const char* JsonHelper::_enumValuesJsonKey = "enumValues"; +const char* JsonHelper::jsonVersionKey = "version"; +const char* JsonHelper::jsonGroundStationKey = "groundStation"; +const char* JsonHelper::jsonGroundStationValue = "QGroundControl"; +const char* JsonHelper::jsonFileTypeKey = "fileType"; bool JsonHelper::validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString) { @@ -108,3 +113,20 @@ bool JsonHelper::parseEnum(QJsonObject& jsonObject, QStringList& enumStrings, QS return true; } + +bool JsonHelper::isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc) +{ + QJsonParseError error; + + jsonDoc = QJsonDocument::fromJson(bytes, &error); + + if (error.error == QJsonParseError::NoError) { + return true; + } + + if (error.error == QJsonParseError::MissingObject && error.offset == 0) { + return false; + } + + return true; +} diff --git a/src/JsonHelper.h b/src/JsonHelper.h index 2396d8b72..adc37658c 100644 --- a/src/JsonHelper.h +++ b/src/JsonHelper.h @@ -7,7 +7,6 @@ * ****************************************************************************/ - #ifndef JsonHelper_H #define JsonHelper_H @@ -17,6 +16,11 @@ class JsonHelper { public: + /// Determines is the specified data is a json file + /// @param jsonDoc Returned json document if json file + /// @return true: file is json, false: file is not json + static bool isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc); + static bool validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString); static bool validateKeyTypes(const QJsonObject& jsonObject, const QStringList& keys, const QList& types, QString& errorString); static bool toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& coordinate, bool altitudeRequired, QString& errorString); @@ -24,6 +28,12 @@ public: static void writeQGeoCoordinate(QJsonValue& jsonValue, const QGeoCoordinate& coordinate, bool writeAltitude); + static const char* jsonVersionKey; + static const char* jsonGroundStationKey; + static const char* jsonGroundStationValue; + static const char* jsonFileTypeKey; + +private: static const char* _enumStringsJsonKey; static const char* _enumValuesJsonKey; }; diff --git a/src/MissionEditor/GeoFenceEditor.qml b/src/MissionEditor/GeoFenceEditor.qml index af02df40e..2c4bd31f9 100644 --- a/src/MissionEditor/GeoFenceEditor.qml +++ b/src/MissionEditor/GeoFenceEditor.qml @@ -18,16 +18,6 @@ QGCFlickable { property var polygon: geoFenceController.polygon - Connections { - target: geoFenceController.polygon - - onPathChanged: { - if (geoFenceController.polygon.path.length > 2) { - geoFenceController.breachReturnPoint = geoFenceController.polygon.center() - } - } - } - Rectangle { id: geoFenceEditorRect width: parent.width diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index bb6c59bbe..d589babb8 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -154,11 +154,33 @@ QGCView { Component.onCompleted: start(true /* editMode */) + function saveToSelectedFile() { + if (ScreenTools.isMobile) { + qgcView.showDialog(mobileFileSaver, qsTr("Save Fence File"), qgcView.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel) + } else { + geoFenceController.saveToFilePicker() + } + } + + function loadFromSelectedFile() { + if (ScreenTools.isMobile) { + qgcView.showDialog(mobileFilePicker, qsTr("Select Fence File"), qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel) + } else { + geoFenceController.loadFromFilePicker() + } + } + onFenceSupportedChanged: { if (!fenceSupported && _editingLayer == _layerGeoFence) { _editingLayer = _layerMission } } + + onBreachReturnPointChanged: { + if (polygon.count() > 3) { + sendToVehicle() + } + } } QGCPalette { id: qgcPal; colorGroupEnabled: enabled } @@ -193,7 +215,7 @@ QGCView { QGCMobileFileDialog { openDialog: true - fileExtension: QGroundControl.missionFileExtension + fileExtension: _syncDropDownController == geoFenceController ? QGroundControl.fenceFileExtension : QGroundControl.missionFileExtension onFilenameReturned: _syncDropDownController.loadFromfile(filename) } } @@ -203,7 +225,7 @@ QGCView { QGCMobileFileDialog { openDialog: false - fileExtension: QGroundControl.missionFileExtension + fileExtension: _syncDropDownController == geoFenceController ? QGroundControl.fenceFileExtension : QGroundControl.missionFileExtension onFilenameReturned: _syncDropDownController.saveToFile() } } @@ -299,6 +321,7 @@ QGCView { } break case _layerGeoFence: + console.log("Updating breach return point", coordinate) geoFenceController.breachReturnPoint = coordinate break } @@ -586,6 +609,7 @@ QGCView { border.color: "#80FF0000" border.width: 3 path: geoFenceController.polygonSupported ? geoFenceController.polygon.path : undefined + z: QGroundControl.zOrderMapItems } // GeoFence circle @@ -594,14 +618,7 @@ QGCView { border.width: 3 center: missionController.plannedHomePosition radius: geoFenceController.circleSupported ? geoFenceController.circleRadius : 0 - } - - // GeoFence circle - MapCircle { - border.color: "#80FF0000" - border.width: 3 - center: missionController.plannedHomePosition - radius: geoFenceController.circleSupported ? geoFenceController.circleRadius : 0 + z: QGroundControl.zOrderMapItems } // GeoFence breach return point @@ -610,6 +627,14 @@ QGCView { coordinate: geoFenceController.breachReturnPoint visible: geoFenceController.breachReturnSupported sourceItem: MissionItemIndexLabel { label: "F" } + z: QGroundControl.zOrderMapItems + + Connections { + target: geoFenceController + onBreachReturnPointChanged: console.log("breachreturn changed inside", geoFenceController.breachReturnPoint) + } + + onCoordinateChanged: console.log("MqpQuickItem coodinateChanged", coordinate) } //-- Dismiss Drop Down (if any) diff --git a/src/MissionEditor/QGCMapPolygonControls.qml b/src/MissionEditor/QGCMapPolygonControls.qml index c14ce2e42..01f520e39 100644 --- a/src/MissionEditor/QGCMapPolygonControls.qml +++ b/src/MissionEditor/QGCMapPolygonControls.qml @@ -14,6 +14,8 @@ Column { property var flightMap ///< Must be set to FlightMap control property var polygon ///< Must be set to MapPolygon + signal polygonEditCompleted ///< Signalled when either a capture or adjust has completed + property real _margin: ScreenTools.defaultFontPixelWidth / 2 function polygonCaptureStarted() { @@ -22,6 +24,7 @@ Column { function polygonCaptureFinished(coordinates) { polygon.path = coordinates + polygonEditCompleted() } function polygonAdjustVertex(vertexIndex, vertexCoordinate) { @@ -29,7 +32,10 @@ Column { } function polygonAdjustStarted() { } - function polygonAdjustFinished() { } + + function polygonAdjustFinished() { + polygonEditCompleted() + } QGCLabel { text: sectionLabel } diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index 1c3094c47..ab3fb2e59 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -16,10 +16,16 @@ #include "FirmwarePlugin.h" #include "MAVLinkProtocol.h" #include "QGCApplication.h" -#include "ParameterLoader.h" +#include "ParameterManager.h" +#include "JsonHelper.h" +#include "QGCFileDialog.h" + +#include QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog") +const char* GeoFenceController::_jsonFileTypeValue = "GeoFence"; + GeoFenceController::GeoFenceController(QObject* parent) : PlanElementController(parent) , _dirty(false) @@ -44,6 +50,7 @@ void GeoFenceController::start(bool editMode) void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint) { if (_breachReturnPoint != breachReturnPoint) { + qDebug() << "GeoFenceController::setBreachReturnPoint" << breachReturnPoint; _breachReturnPoint = breachReturnPoint; setDirty(true); emit breachReturnPointChanged(breachReturnPoint); @@ -56,6 +63,7 @@ void GeoFenceController::_signalAll(void) emit circleSupportedChanged(circleSupported()); emit polygonSupportedChanged(polygonSupported()); emit breachReturnSupportedChanged(breachReturnSupported()); + emit breachReturnPointChanged(breachReturnPoint()); emit circleRadiusChanged(circleRadius()); emit paramsChanged(params()); emit paramLabelsChanged(paramLabels()); @@ -84,35 +92,203 @@ void GeoFenceController::_activeVehicleSet(void) connect(geoFenceManager, &GeoFenceManager::paramsChanged, this, &GeoFenceController::paramsChanged); connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged, this, &GeoFenceController::paramLabelsChanged); + _setPolygon(geoFenceManager->polygon()); + setBreachReturnPoint(geoFenceManager->breachReturnPoint()); + _signalAll(); +} - if (_activeVehicle->getParameterLoader()->parametersAreReady()) { - if (!syncInProgress()) { - // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle. - // We don't request mission items for new vehicles since that will happen autamatically. - loadFromVehicle(); - } +bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString) +{ + QJsonObject json = jsonDoc.object(); + + // Check for required keys + QStringList requiredKeys; + requiredKeys << JsonHelper::jsonVersionKey << JsonHelper::jsonFileTypeKey; + if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) { + return false; + } + +#if 0 + // Validate base key types + QStringList keyList; + QList typeList; + keyList << jsonSimpleItemsKey << _jsonVersionKey << _jsonGroundStationKey << _jsonMavAutopilotKey << _jsonComplexItemsKey << _jsonPlannedHomePositionKey; + typeList << QJsonValue::Array << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Object; + if (!JsonHelper::validateKeyTypes(json, keyList, typeList, errorString)) { + return false; } +#endif + + // Version check + if (json[JsonHelper::jsonVersionKey].toString() != "1.0") { + errorString = QStringLiteral("QGroundControl does not support this file version"); + return false; + } + + if (!_activeVehicle->getParameterManager()->loadFromJson(json, false /* required */, errorString)) { + return false; + } + + if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) { + return false; + } + + return true; } -void GeoFenceController::loadFromFilePicker(void) +#if 0 +// NYI +bool GeoFenceController::_loadTextFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString) { + bool addPlannedHomePosition = false; + + QString firstLine = stream.readLine(); + const QStringList& version = firstLine.split(" "); + + bool versionOk = false; + if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") { + if (version[2] == "110") { + // ArduPilot file, planned home position is already in position 0 + versionOk = true; + } else if (version[2] == "120") { + // Old QGC file, no planned home position + versionOk = true; + addPlannedHomePosition = true; + } + } + + if (versionOk) { + while (!stream.atEnd()) { + SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this); + + if (item->load(stream)) { + visualItems->append(item); + } else { + errorString = QStringLiteral("The mission file is corrupted."); + return false; + } + } + } else { + errorString = QStringLiteral("The mission file is not compatible with this version of QGroundControl."); + return false; + } + + if (addPlannedHomePosition || visualItems->count() == 0) { + _addPlannedHomePosition(visualItems, true /* addToCenter */); + // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0 + for (int i=1; icount(); i++) { + SimpleMissionItem* item = qobject_cast(visualItems->get(i)); + if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) { + item->missionItem().setParam1((int)item->missionItem().param1() + 1); + } + } + } + + return true; } +#endif void GeoFenceController::loadFromFile(const QString& filename) { - Q_UNUSED(filename); + QString errorString; + + if (filename.isEmpty()) { + return; + } + + QFile file(filename); + + if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { + errorString = file.errorString(); + } else { + QJsonDocument jsonDoc; + QByteArray bytes = file.readAll(); + + if (JsonHelper::isJsonFile(bytes, jsonDoc)) { + _loadJsonFile(jsonDoc, errorString); + } else { + // FIXME: No MP file format support + qgcApp()->showMessage("GeoFence file is in incorrect format."); + return; + } + } + + if (!errorString.isEmpty()) { + qgcApp()->showMessage(errorString); + } + + setDirty(false); } -void GeoFenceController::saveToFilePicker(void) +void GeoFenceController::loadFromFilePicker(void) { +#ifndef __mobile__ + QString filename = QGCFileDialog::getOpenFileName(NULL, "Select GeoFence File to load", QString(), "Mission file (*.fence);;All Files (*.*)"); + if (filename.isEmpty()) { + return; + } + loadFromFile(filename); +#endif } void GeoFenceController::saveToFile(const QString& filename) { - Q_UNUSED(filename); + qDebug() << filename; + + if (filename.isEmpty()) { + return; + } + + QString fenceFilename = filename; + if (!QFileInfo(filename).fileName().contains(".")) { + fenceFilename += QString(".%1").arg(QGCApplication::fenceFileExtension); + } + + QFile file(fenceFilename); + + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { + qgcApp()->showMessage(file.errorString()); + } else { + QJsonObject fenceFileObject; // top level json object + + fenceFileObject[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue; + fenceFileObject[JsonHelper::jsonVersionKey] = QStringLiteral("1.0"); + fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; + + QStringList paramNames; + ParameterManager* paramMgr = _activeVehicle->getParameterManager(); + GeoFenceManager* fenceMgr = _activeVehicle->geoFenceManager(); + QVariantList params = fenceMgr->params(); + + for (int i=0; i< params.count(); i++) { + paramNames.append(params[i].value()->name()); + } + if (paramNames.count() > 0) { + paramMgr->saveToJson(paramMgr->defaultComponentId(), paramNames, fenceFileObject); + } + + _polygon.saveToJson(fenceFileObject); + + QJsonDocument saveDoc(fenceFileObject); + file.write(saveDoc.toJson()); + } + + setDirty(false); +} + +void GeoFenceController::saveToFilePicker(void) +{ +#ifndef __mobile__ + QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save GeoFence to", QString(), "Fence file (*.fence);;All Files (*.*)"); + + if (filename.isEmpty()) { + return; + } + saveToFile(filename); +#endif } void GeoFenceController::removeAll(void) @@ -122,23 +298,23 @@ void GeoFenceController::removeAll(void) void GeoFenceController::loadFromVehicle(void) { - if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { _activeVehicle->geoFenceManager()->loadFromVehicle(); } else { - qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterLoader()->parametersAreReady() << syncInProgress(); + qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress(); } } void GeoFenceController::sendToVehicle(void) { - if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { _activeVehicle->geoFenceManager()->setPolygon(polygon()); _activeVehicle->geoFenceManager()->setBreachReturnPoint(breachReturnPoint()); setDirty(false); _polygon.setDirty(false); _activeVehicle->geoFenceManager()->sendToVehicle(); } else { - qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterLoader()->parametersAreReady() << syncInProgress(); + qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress(); } } diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index 413c0cfda..842b4af9b 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -19,6 +19,8 @@ Q_DECLARE_LOGGING_CATEGORY(GeoFenceControllerLog) +class GeoFenceManager; + class GeoFenceController : public PlanElementController { Q_OBJECT @@ -84,14 +86,17 @@ private slots: private: void _clearGeoFence(void); void _signalAll(void); + bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString); void _activeVehicleBeingRemoved(void) final; void _activeVehicleSet(void) final; - bool _dirty; - QGCMapPolygon _polygon; - QGeoCoordinate _breachReturnPoint; - QVariantList _params; + bool _dirty; + QGCMapPolygon _polygon; + QGeoCoordinate _breachReturnPoint; + QVariantList _params; + + static const char* _jsonFileTypeValue; }; #endif diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 848ec8da5..3e0f10797 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -17,7 +17,7 @@ #include "SimpleMissionItem.h" #include "SurveyMissionItem.h" #include "JsonHelper.h" -#include "ParameterLoader.h" +#include "ParameterManager.h" #include "QGroundControlQmlGlobal.h" #ifndef __mobile__ @@ -29,8 +29,6 @@ QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog") const char* MissionController::jsonSimpleItemsKey = "items"; const char* MissionController::_settingsGroup = "MissionController"; -const char* MissionController::_jsonVersionKey = "version"; -const char* MissionController::_jsonGroundStationKey = "groundStation"; const char* MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT"; const char* MissionController::_jsonComplexItemsKey = "complexItems"; const char* MissionController::_jsonPlannedHomePositionKey = "plannedHomePosition"; @@ -258,7 +256,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL // Check for required keys QStringList requiredKeys; - requiredKeys << _jsonVersionKey << _jsonPlannedHomePositionKey; + requiredKeys << JsonHelper::jsonVersionKey << _jsonPlannedHomePositionKey; if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) { return false; } @@ -266,14 +264,14 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL // Validate base key types QStringList keyList; QList typeList; - keyList << jsonSimpleItemsKey << _jsonVersionKey << _jsonGroundStationKey << _jsonMavAutopilotKey << _jsonComplexItemsKey << _jsonPlannedHomePositionKey; + keyList << jsonSimpleItemsKey << JsonHelper::jsonVersionKey << JsonHelper::jsonGroundStationKey << _jsonMavAutopilotKey << _jsonComplexItemsKey << _jsonPlannedHomePositionKey; typeList << QJsonValue::Array << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Object; if (!JsonHelper::validateKeyTypes(json, keyList, typeList, errorString)) { return false; } // Version check - if (json[_jsonVersionKey].toString() != "1.0") { + if (json[JsonHelper::jsonVersionKey].toString() != "1.0") { errorString = QStringLiteral("QGroundControl does not support this file version"); return false; } @@ -502,8 +500,8 @@ void MissionController::saveToFile(const QString& filename) QJsonArray simpleItemsObject; QJsonArray complexItemsObject; - missionFileObject[_jsonVersionKey] = "1.0"; - missionFileObject[_jsonGroundStationKey] = "QGroundControl"; + missionFileObject[JsonHelper::jsonVersionKey] = "1.0"; + missionFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; MAV_AUTOPILOT firmwareType = MAV_AUTOPILOT_GENERIC; if (_activeVehicle) { @@ -1054,7 +1052,7 @@ void MissionController::_activeVehicleSet(void) connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); - if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle. // We don't request mission items for new vehicles since that will happen autamatically. loadFromVehicle(); diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index c82c74eeb..63abcb20d 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -148,8 +148,6 @@ private: double _hoverDistance; static const char* _settingsGroup; - static const char* _jsonVersionKey; - static const char* _jsonGroundStationKey; static const char* _jsonMavAutopilotKey; static const char* _jsonComplexItemsKey; static const char* _jsonPlannedHomePositionKey; diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index 060eb10bf..c469b6905 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -9,10 +9,14 @@ #include "QGCMapPolygon.h" #include "QGCGeo.h" +#include "JsonHelper.h" #include #include #include +#include + +const char* QGCMapPolygon::_jsonPolygonKey = "polygon"; QGCMapPolygon::QGCMapPolygon(QObject* parent) : QObject(parent) @@ -106,3 +110,56 @@ void QGCMapPolygon::setPath(const QVariantList& path) setDirty(true); emit pathChanged(); } + +void QGCMapPolygon::saveToJson(QJsonObject& json) +{ + QJsonArray rgPoints; + + // Add all points to the array + for (int i=0; i<_polygonPath.count(); i++) { + QJsonValue jsonPoint; + + JsonHelper::writeQGeoCoordinate(jsonPoint, (*this)[i], false /* writeAltitude */); + rgPoints.append(jsonPoint); + } + + json.insert(_jsonPolygonKey, QJsonValue(rgPoints)); + + setDirty(false); +} + +bool QGCMapPolygon::loadFromJson(const QJsonObject& json, bool required, QString& errorString) +{ + errorString.clear(); + clear(); + + if (required) { + if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonPolygonKey), errorString)) { + return false; + } + } else if (!json.contains(_jsonPolygonKey)) { + return true; + } + + QList types; + + types << QJsonValue::Array; + if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonPolygonKey), types, errorString)) { + return false; + } + + QJsonArray rgPoints = json[_jsonPolygonKey].toArray(); + for (int i=0; i typeList; - keyList << _jsonVersionKey << _jsonTypeKey << _jsonIdKey << _jsonPolygonKey << _jsonGridAltitudeKey << _jsonGridAngleKey << _jsonGridSpacingKey << _jsonTurnaroundDistKey << + keyList << JsonHelper::jsonVersionKey << _jsonTypeKey << _jsonIdKey << _jsonPolygonKey << _jsonGridAltitudeKey << _jsonGridAngleKey << _jsonGridSpacingKey << _jsonTurnaroundDistKey << _jsonCameraTriggerKey << _jsonCameraTriggerDistanceKey << _jsonGridAltitudeRelativeKey; typeList << QJsonValue::Double << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Double << QJsonValue::Double<< QJsonValue::Double << QJsonValue::Double << QJsonValue::Bool << QJsonValue::Double << QJsonValue::Bool; @@ -266,7 +265,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, QString& errorStr } // Version check - if (complexObject[_jsonVersionKey].toInt() != 1) { + if (complexObject[JsonHelper::jsonVersionKey].toInt() != 1) { errorString = tr("QGroundControl does not support this version of survey items"); _clear(); return false; diff --git a/src/MissionManager/SurveyMissionItem.h b/src/MissionManager/SurveyMissionItem.h index fb778a6c2..d31ed97fb 100644 --- a/src/MissionManager/SurveyMissionItem.h +++ b/src/MissionManager/SurveyMissionItem.h @@ -140,7 +140,6 @@ private: FactMetaData _turnaroundDistMetaData; FactMetaData _cameraTriggerDistanceMetaData; - static const char* _jsonVersionKey; static const char* _jsonTypeKey; static const char* _jsonPolygonKey; static const char* _jsonIdKey; diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 02f7ed363..aff3a4d23 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -124,6 +124,7 @@ QGCApplication* QGCApplication::_app = NULL; const char* QGCApplication::parameterFileExtension = "params"; const char* QGCApplication::missionFileExtension = "mission"; +const char* QGCApplication::fenceFileExtension = "fence"; const char* QGCApplication::telemetryFileExtension = "tlog"; const char* QGCApplication::_deleteAllSettingsKey = "DeleteAllSettingsNextBoot"; @@ -305,7 +306,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION); // Clear parameter cache - QDir paramDir(ParameterLoader::parameterCacheDir()); + QDir paramDir(ParameterManager::parameterCacheDir()); paramDir.removeRecursively(); paramDir.mkpath(paramDir.absolutePath()); } else { diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 52e970101..0d9d38efd 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -67,6 +67,7 @@ public: static const char* parameterFileExtension; static const char* missionFileExtension; + static const char* fenceFileExtension; static const char* telemetryFileExtension; /// @brief Sets the persistent flag to delete all settings the next time QGroundControl is started. -- 2.22.0