diff --git a/.ci/Jenkinsfile-SITL_tests b/.ci/Jenkinsfile-SITL_tests
index aa722c9c08..7df3048560 100644
--- a/.ci/Jenkinsfile-SITL_tests
+++ b/.ci/Jenkinsfile-SITL_tests
@@ -42,27 +42,16 @@ pipeline {
script {
def missions = [
[
- name: "VTOL standard",
+ name: "FW",
test: "mavros_posix_test_mission.test",
- mission: "vtol_new_1",
- vehicle: "standard_vtol"
- ],
- [
- name: "VTOL tailsitter",
- test: "mavros_posix_test_mission.test",
- mission: "vtol_new_1",
- vehicle: "tailsitter"
- ],
- [
- name: "VTOL tiltrotor",
- test: "mavros_posix_test_mission.test",
- mission: "vtol_new_1",
- vehicle: "tiltrotor"
+ mission: "FW_mission_1",
+ vehicle: "plane"
],
+
[
name: "MC box",
test: "mavros_posix_test_mission.test",
- mission: "multirotor_box",
+ mission: "MC_mission_box",
vehicle: "iris"
],
[
@@ -76,7 +65,27 @@ pipeline {
test: "mavros_posix_tests_offboard_posctl.test",
mission: "",
vehicle: "iris"
- ]
+ ],
+
+ [
+ name: "VTOL standard",
+ test: "mavros_posix_test_mission.test",
+ mission: "VTOL_mission_1",
+ vehicle: "standard_vtol"
+ ],
+ [
+ name: "VTOL tailsitter",
+ test: "mavros_posix_test_mission.test",
+ mission: "VTOL_mission_1",
+ vehicle: "tailsitter"
+ ],
+ [
+ name: "VTOL tiltrotor",
+ test: "mavros_posix_test_mission.test",
+ mission: "VTOL_mission_1",
+ vehicle: "tiltrotor"
+ ],
+
]
def test_nodes = [:]
diff --git a/Makefile b/Makefile
index cc6727be0a..f682c4f2ad 100644
--- a/Makefile
+++ b/Makefile
@@ -306,7 +306,7 @@ tests_mission_coverage:
@$(MAKE) clean
@$(MAKE) --no-print-directory posix_sitl_default PX4_CMAKE_BUILD_TYPE=Coverage
@$(MAKE) --no-print-directory posix_sitl_default sitl_gazebo PX4_CMAKE_BUILD_TYPE=Coverage
- @$(SRC_DIR)/test/rostest_px4_run.sh mavros_posix_test_mission.test mission:=vtol_new_1 vehicle:=standard_vtol
+ @$(SRC_DIR)/test/rostest_px4_run.sh mavros_posix_test_mission.test mission:=VTOL_mission_1 vehicle:=standard_vtol
@$(MAKE) --no-print-directory posix_sitl_default generate_coverage
tests_offboard: rostest
diff --git a/ROMFS/px4fmu_common/init.d-posix/1030_plane b/ROMFS/px4fmu_common/init.d-posix/1030_plane
index 8b85c0ec8a..4884cee3d9 100644
--- a/ROMFS/px4fmu_common/init.d-posix/1030_plane
+++ b/ROMFS/px4fmu_common/init.d-posix/1030_plane
@@ -14,6 +14,7 @@ then
param set EKF2_MAG_ACCLIM 0
param set EKF2_MAG_YAWLIM 0
+ param set FW_LND_AIRSPD_SC 1
param set FW_LND_ANG 8
param set FW_P_TC 0.5
param set FW_PR_FF 0.40
diff --git a/integrationtests/python_src/px4_it/mavros/missions/vtol_new_2.plan b/integrationtests/python_src/px4_it/mavros/missions/FW_mission_1.plan
similarity index 70%
rename from integrationtests/python_src/px4_it/mavros/missions/vtol_new_2.plan
rename to integrationtests/python_src/px4_it/mavros/missions/FW_mission_1.plan
index 3678c7c0b1..67bbed1927 100644
--- a/integrationtests/python_src/px4_it/mavros/missions/vtol_new_2.plan
+++ b/integrationtests/python_src/px4_it/mavros/missions/FW_mission_1.plan
@@ -1,6 +1,11 @@
{
"fileType": "Plan",
"geoFence": {
+ "circles": [
+ ],
+ "polygons": [
+ ],
+ "version": 2
},
"groundStation": "QGroundControl",
"mission": {
@@ -10,10 +15,10 @@
"items": [
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 50,
"AltitudeMode": 0,
"autoContinue": true,
- "command": 84,
+ "command": 22,
"doJumpId": 1,
"frame": 3,
"params": [
@@ -21,15 +26,15 @@
0,
0,
null,
- 47.39774638739962,
- 8.545592088860758,
- 12
+ 47.397856910618785,
+ 8.542576533916815,
+ 50
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 50,
"AltitudeMode": 0,
"autoContinue": true,
"command": 16,
@@ -40,47 +45,44 @@
0,
0,
null,
- 47.3981026817918,
- 8.548114267064136,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 50,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 3,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.39995383332046,
- 8.54783592762601,
+ 47.39602683906673,
+ 8.539868609985234,
50
],
"type": "SimpleItem"
},
{
- "AMSLAltAboveTerrain": null,
- "Altitude": 20,
- "AltitudeMode": 0,
"autoContinue": true,
- "command": 16,
- "doJumpId": 4,
- "frame": 3,
+ "command": 189,
+ "doJumpId": 3,
+ "frame": 2,
"params": [
0,
0,
0,
- null,
- 47.39998472464772,
- 8.544660189638307,
- 20
+ 0,
+ 0,
+ 0,
+ 0
+ ],
+ "type": "SimpleItem"
+ },
+ {
+ "AMSLAltAboveTerrain": null,
+ "Altitude": 25,
+ "AltitudeMode": 0,
+ "autoContinue": true,
+ "command": 31,
+ "doJumpId": 4,
+ "frame": 3,
+ "params": [
+ 1,
+ 50,
+ 0,
+ 1,
+ 47.39537936180079,
+ 8.543743516831427,
+ 25
],
"type": "SimpleItem"
},
@@ -89,33 +91,33 @@
"Altitude": 0,
"AltitudeMode": 0,
"autoContinue": true,
- "command": 85,
+ "command": 21,
"doJumpId": 5,
"frame": 3,
"params": [
- 0,
+ 25,
0,
0,
null,
- 47.39903545,
- 8.54322638,
+ 47.39733554489375,
+ 8.545863573918894,
0
],
"type": "SimpleItem"
}
],
"plannedHomePosition": [
- 47.3977419,
- 8.5455943,
- 489
+ 47.397742,
+ 8.545594,
+ 488
],
- "vehicleType": 20,
+ "vehicleType": 1,
"version": 2
},
"rallyPoints": {
"points": [
],
- "version": 1
+ "version": 2
},
"version": 1
}
diff --git a/integrationtests/python_src/px4_it/mavros/missions/vtol_old_2.plan b/integrationtests/python_src/px4_it/mavros/missions/MC_mission_box.plan
similarity index 65%
rename from integrationtests/python_src/px4_it/mavros/missions/vtol_old_2.plan
rename to integrationtests/python_src/px4_it/mavros/missions/MC_mission_box.plan
index d923400e8e..8e2b37540b 100644
--- a/integrationtests/python_src/px4_it/mavros/missions/vtol_old_2.plan
+++ b/integrationtests/python_src/px4_it/mavros/missions/MC_mission_box.plan
@@ -1,6 +1,11 @@
{
"fileType": "Plan",
"geoFence": {
+ "circles": [
+ ],
+ "polygons": [
+ ],
+ "version": 2
},
"groundStation": "QGroundControl",
"mission": {
@@ -10,7 +15,7 @@
"items": [
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 5,
"AltitudeMode": 0,
"autoContinue": true,
"command": 22,
@@ -21,31 +26,34 @@
0,
0,
null,
- 47.39774072271174,
- 8.545594410269672,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 3000,
- "doJumpId": 2,
- "frame": 2,
- "params": [
- 4,
- 0,
- 0,
- 0,
- 47.39773238,
- 8.54582241,
- 12
+ 47.39773941040039,
+ 8.5455904006958,
+ 5
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 10,
+ "AltitudeMode": 0,
+ "autoContinue": true,
+ "command": 16,
+ "doJumpId": 2,
+ "frame": 3,
+ "params": [
+ 0,
+ 0,
+ 0,
+ null,
+ 47.39787292480469,
+ 8.54559326171875,
+ 10
+ ],
+ "type": "SimpleItem"
+ },
+ {
+ "AMSLAltAboveTerrain": null,
+ "Altitude": 10,
"AltitudeMode": 0,
"autoContinue": true,
"command": 16,
@@ -55,16 +63,16 @@
0,
0,
0,
- 0,
- 47.39693448800759,
- 8.540991562303702,
- 12
+ null,
+ 47.39787292480469,
+ 8.545341491699219,
+ 10
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 10,
"AltitudeMode": 0,
"autoContinue": true,
"command": 16,
@@ -75,60 +83,63 @@
0,
0,
null,
- 47.39921311963185,
- 8.543012487901848,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 3000,
- "doJumpId": 5,
- "frame": 2,
- "params": [
- 3,
- 0,
- 0,
- 0,
- 47.3991589,
- 8.54290773,
- 12
+ 47.39773941040039,
+ 8.545336723327637,
+ 10
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 10,
+ "AltitudeMode": 0,
+ "autoContinue": true,
+ "command": 16,
+ "doJumpId": 5,
+ "frame": 3,
+ "params": [
+ 0,
+ 0,
+ 0,
+ null,
+ 47.39773941040039,
+ 8.5455904006958,
+ 10
+ ],
+ "type": "SimpleItem"
+ },
+ {
+ "AMSLAltAboveTerrain": null,
+ "Altitude": 0,
"AltitudeMode": 0,
"autoContinue": true,
"command": 21,
"doJumpId": 6,
"frame": 3,
"params": [
- 25,
+ 0,
0,
0,
null,
- 47.39921188354492,
- 8.543012344844442,
- 12
+ 47.39773941040039,
+ 8.545591354370117,
+ 0
],
"type": "SimpleItem"
}
],
"plannedHomePosition": [
- 47.3977419,
- 8.5455943,
- 489
+ 47.397742,
+ 8.545594,
+ 488
],
- "vehicleType": 20,
+ "vehicleType": 2,
"version": 2
},
"rallyPoints": {
"points": [
],
- "version": 1
+ "version": 2
},
"version": 1
}
diff --git a/integrationtests/python_src/px4_it/mavros/missions/vtol_old_3.plan b/integrationtests/python_src/px4_it/mavros/missions/VTOL_mission_1.plan
similarity index 65%
rename from integrationtests/python_src/px4_it/mavros/missions/vtol_old_3.plan
rename to integrationtests/python_src/px4_it/mavros/missions/VTOL_mission_1.plan
index d595c3cb51..6aee1738b0 100644
--- a/integrationtests/python_src/px4_it/mavros/missions/vtol_old_3.plan
+++ b/integrationtests/python_src/px4_it/mavros/missions/VTOL_mission_1.plan
@@ -1,6 +1,11 @@
{
"fileType": "Plan",
"geoFence": {
+ "circles": [
+ ],
+ "polygons": [
+ ],
+ "version": 2
},
"groundStation": "QGroundControl",
"mission": {
@@ -10,10 +15,10 @@
"items": [
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 15,
"AltitudeMode": 0,
"autoContinue": true,
- "command": 16,
+ "command": 84,
"doJumpId": 1,
"frame": 3,
"params": [
@@ -21,34 +26,37 @@
0,
0,
null,
- 47.398157669127094,
- 8.546033631711538,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 3000,
- "doJumpId": 2,
- "frame": 2,
- "params": [
- 4,
- 0,
- 0,
- 0,
- 47.398033142089844,
- 8.54578971862793,
- 12
+ 47.397731862593744,
+ 8.543269295853861,
+ 15
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
- "Altitude": 12,
+ "Altitude": 15,
"AltitudeMode": 0,
"autoContinue": true,
"command": 16,
+ "doJumpId": 2,
+ "frame": 3,
+ "params": [
+ 0,
+ 0,
+ 0,
+ null,
+ 47.39666467622327,
+ 8.540909537045792,
+ 15
+ ],
+ "type": "SimpleItem"
+ },
+ {
+ "AMSLAltAboveTerrain": null,
+ "Altitude": 0,
+ "AltitudeMode": 0,
+ "autoContinue": true,
+ "command": 85,
"doJumpId": 3,
"frame": 3,
"params": [
@@ -56,17 +64,17 @@
0,
0,
null,
- 47.400993929351195,
- 8.544680403485842,
- 12
+ 47.39615608503663,
+ 8.54513863086865,
+ 0
],
"type": "SimpleItem"
}
],
"plannedHomePosition": [
- 47.3977419,
- 8.5455943,
- 489
+ 47.397742,
+ 8.545594,
+ 488
],
"vehicleType": 20,
"version": 2
@@ -74,7 +82,7 @@
"rallyPoints": {
"points": [
],
- "version": 1
+ "version": 2
},
"version": 1
}
diff --git a/integrationtests/python_src/px4_it/mavros/missions/multirotor_box.plan b/integrationtests/python_src/px4_it/mavros/missions/multirotor_box.plan
deleted file mode 100644
index 9698588199..0000000000
--- a/integrationtests/python_src/px4_it/mavros/missions/multirotor_box.plan
+++ /dev/null
@@ -1,125 +0,0 @@
-{
- "fileType": "Plan",
- "geoFence": {
- "polygon": [
- ],
- "version": 1
- },
- "groundStation": "QGroundControl",
- "mission": {
- "cruiseSpeed": 15,
- "firmwareType": 12,
- "hoverSpeed": 5,
- "items": [
- {
- "autoContinue": true,
- "command": 22,
- "doJumpId": 1,
- "frame": 3,
- "params": [
- 15.0,
- 0,
- 0,
- null,
- 47.397739410400391,
- 8.5455904006958008,
- 5.0
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 16,
- "doJumpId": 2,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.397872924804688,
- 8.54559326171875,
- 5.0
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 16,
- "doJumpId": 3,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.397872924804688,
- 8.5453414916992188,
- 5.0
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 16,
- "doJumpId": 4,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.397739410400391,
- 8.5453367233276367,
- 5.0
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 16,
- "doJumpId": 5,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.397739410400391,
- 8.5455904006958008,
- 5.0
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 21,
- "doJumpId": 6,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.397739410400391,
- 8.5455913543701172,
- 5.0
- ],
- "type": "SimpleItem"
- }
- ],
- "plannedHomePosition": [
- 47.397742,
- 8.545594,
- 12.0
- ],
- "vehicleType": 2,
- "version": 2
- },
- "rallyPoints": {
- "points": [
- ],
- "version": 1
- },
- "version": 1
-}
diff --git a/integrationtests/python_src/px4_it/mavros/missions/vtol_new_1.plan b/integrationtests/python_src/px4_it/mavros/missions/vtol_new_1.plan
deleted file mode 100644
index e4461ad0e3..0000000000
--- a/integrationtests/python_src/px4_it/mavros/missions/vtol_new_1.plan
+++ /dev/null
@@ -1,61 +0,0 @@
-{
- "fileType": "Plan",
- "geoFence": {
- "polygon": [
- ],
- "version": 1
- },
- "groundStation": "QGroundControl",
- "mission": {
- "cruiseSpeed": 15,
- "firmwareType": 12,
- "hoverSpeed": 5,
- "items": [
- {
- "autoContinue": true,
- "command": 84,
- "doJumpId": 1,
- "frame": 3,
- "params": [
- 15.0,
- 0,
- 0,
- null,
- 47.397731862593744,
- 8.543269295853861,
- 15.0
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 85,
- "doJumpId": 2,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.39651890962795,
- 8.5433217125134888,
- 0.0
- ],
- "type": "SimpleItem"
- }
- ],
- "plannedHomePosition": [
- 47.397742,
- 8.545594,
- 12.0
- ],
- "vehicleType": 19,
- "version": 2
- },
- "rallyPoints": {
- "points": [
- ],
- "version": 1
- },
- "version": 1
-}
diff --git a/integrationtests/python_src/px4_it/mavros/missions/vtol_old_1.plan b/integrationtests/python_src/px4_it/mavros/missions/vtol_old_1.plan
deleted file mode 100644
index d0175fc5d3..0000000000
--- a/integrationtests/python_src/px4_it/mavros/missions/vtol_old_1.plan
+++ /dev/null
@@ -1,210 +0,0 @@
-{
- "fileType": "Plan",
- "geoFence": {
- },
- "groundStation": "QGroundControl",
- "mission": {
- "cruiseSpeed": 15,
- "firmwareType": 12,
- "hoverSpeed": 5,
- "items": [
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 22,
- "doJumpId": 1,
- "frame": 3,
- "params": [
- 15,
- 0,
- 0,
- null,
- 47.39804640668762,
- 8.54583667211159,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 3000,
- "doJumpId": 2,
- "frame": 2,
- "params": [
- 4,
- 0,
- 0,
- 0,
- 47.398033142089844,
- 8.54578971862793,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 3,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.398882302443944,
- 8.544601519419729,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 4,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.399831101001084,
- 8.54424775753435,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 5,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.400661353275886,
- 8.544699555148952,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 6,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.40083843752823,
- 8.546172909420818,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 7,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.40019385680461,
- 8.547528070486777,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 16,
- "doJumpId": 8,
- "frame": 3,
- "params": [
- 0,
- 0,
- 0,
- null,
- 47.39928114568153,
- 8.547910568913295,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "autoContinue": true,
- "command": 3000,
- "doJumpId": 9,
- "frame": 2,
- "params": [
- 3,
- 0,
- 0,
- 0,
- 47.39778518676758,
- 8.545262336730957,
- 12
- ],
- "type": "SimpleItem"
- },
- {
- "AMSLAltAboveTerrain": null,
- "Altitude": 12,
- "AltitudeMode": 0,
- "autoContinue": true,
- "command": 21,
- "doJumpId": 10,
- "frame": 3,
- "params": [
- 25,
- 0,
- 0,
- null,
- 47.398884865088675,
- 8.547918116539563,
- 12
- ],
- "type": "SimpleItem"
- }
- ],
- "plannedHomePosition": [
- 47.3977419,
- 8.5455943,
- 489
- ],
- "vehicleType": 20,
- "version": 2
- },
- "rallyPoints": {
- "points": [
- ],
- "version": 1
- },
- "version": 1
-}
diff --git a/test/mavros_posix_tests_missions.test b/test/mavros_posix_tests_missions.test
index 2aec66c6b8..df892fcd57 100644
--- a/test/mavros_posix_tests_missions.test
+++ b/test/mavros_posix_tests_missions.test
@@ -16,10 +16,9 @@
-
-
-
-
-
-
+
+
+
+
+