mirror of https://github.com/ArduPilot/ardupilot
autotest: plane: enable ICE frames in FlyEachFrame
Now that starter control is an aux channel, engine commands are no longer blocked by default, so it's easy to enable ICE frames by adding an engine start command to the beginning of the missions.
This commit is contained in:
parent
b908f1cb9c
commit
3982d576eb
|
@ -1,13 +1,14 @@
|
||||||
QGC WPL 110
|
QGC WPL 110
|
||||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
||||||
1 0 3 84 0.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
1 0 0 223 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
2 0 3 84 0.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||||
6 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||||
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
7 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
8 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||||
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||||
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||||
11 0 3 85 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
11 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||||
|
12 0 3 85 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
||||||
|
|
|
@ -1,13 +1,14 @@
|
||||||
QGC WPL 110
|
QGC WPL 110
|
||||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
|
||||||
1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
1 0 0 223 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
2 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
|
||||||
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
|
||||||
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
|
||||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
|
||||||
6 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
|
||||||
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
7 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
8 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
|
||||||
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
|
||||||
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
|
||||||
11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
11 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
|
||||||
|
12 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1
|
||||||
|
|
|
@ -4201,8 +4201,6 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||||
vinfo_options = vinfo.options[self.vehicleinfo_key()]
|
vinfo_options = vinfo.options[self.vehicleinfo_key()]
|
||||||
known_broken_frames = {
|
known_broken_frames = {
|
||||||
"plane-tailsitter": "unstable in hover; unflyable in cruise",
|
"plane-tailsitter": "unstable in hover; unflyable in cruise",
|
||||||
"plane-ice" : "needs ICE control channel for ignition",
|
|
||||||
"quadplane-ice" : "needs ICE control channel for ignition",
|
|
||||||
"quadplane-can" : "needs CAN periph",
|
"quadplane-can" : "needs CAN periph",
|
||||||
"stratoblimp" : "not expected to fly normally",
|
"stratoblimp" : "not expected to fly normally",
|
||||||
"glider" : "needs balloon lift",
|
"glider" : "needs balloon lift",
|
||||||
|
|
|
@ -1,5 +1,6 @@
|
||||||
ICE_ENABLE 1
|
ICE_ENABLE 1
|
||||||
ICE_RPM_CHAN 1
|
ICE_RPM_CHAN 1
|
||||||
|
ICE_RPM_THRESH 50
|
||||||
SERVO13_FUNCTION 67
|
SERVO13_FUNCTION 67
|
||||||
SERVO14_FUNCTION 69
|
SERVO14_FUNCTION 69
|
||||||
RC11_OPTION 179
|
RC11_OPTION 179
|
||||||
|
|
Loading…
Reference in New Issue