diff --git a/posix-configs/SITL/init/ekf2/iris b/posix-configs/SITL/init/ekf2/iris index 06850bfee9..60e0229e1b 100644 --- a/posix-configs/SITL/init/ekf2/iris +++ b/posix-configs/SITL/init/ekf2/iris @@ -53,7 +53,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/ekf2/iris_opt_flow b/posix-configs/SITL/init/ekf2/iris_opt_flow index 8019903c33..f55a783a92 100644 --- a/posix-configs/SITL/init/ekf2/iris_opt_flow +++ b/posix-configs/SITL/init/ekf2/iris_opt_flow @@ -55,7 +55,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/ekf2/multiple_iris b/posix-configs/SITL/init/ekf2/multiple_iris index 22a85cc815..1af538e9d0 100644 --- a/posix-configs/SITL/init/ekf2/multiple_iris +++ b/posix-configs/SITL/init/ekf2/multiple_iris @@ -53,7 +53,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/ekf2/plane b/posix-configs/SITL/init/ekf2/plane index 521b5a6e21..4a367861bc 100644 --- a/posix-configs/SITL/init/ekf2/plane +++ b/posix-configs/SITL/init/ekf2/plane @@ -60,7 +60,6 @@ adcsim start gpssim start measairspeedsim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start navigator start diff --git a/posix-configs/SITL/init/ekf2/solo b/posix-configs/SITL/init/ekf2/solo index ac8d44e84c..16370bca8d 100644 --- a/posix-configs/SITL/init/ekf2/solo +++ b/posix-configs/SITL/init/ekf2/solo @@ -50,7 +50,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/ekf2/standard_vtol b/posix-configs/SITL/init/ekf2/standard_vtol index f1abfcb8c1..653baf9d87 100644 --- a/posix-configs/SITL/init/ekf2/standard_vtol +++ b/posix-configs/SITL/init/ekf2/standard_vtol @@ -68,7 +68,6 @@ adcsim start gpssim start measairspeedsim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/ekf2/tailsitter b/posix-configs/SITL/init/ekf2/tailsitter index 13faecfdcb..83ed7b3e2b 100644 --- a/posix-configs/SITL/init/ekf2/tailsitter +++ b/posix-configs/SITL/init/ekf2/tailsitter @@ -50,7 +50,6 @@ adcsim start gpssim start measairspeedsim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/ekf2/typhoon_h480 b/posix-configs/SITL/init/ekf2/typhoon_h480 index bc60d1147d..7ad337421e 100644 --- a/posix-configs/SITL/init/ekf2/typhoon_h480 +++ b/posix-configs/SITL/init/ekf2/typhoon_h480 @@ -52,7 +52,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm16 -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/inav/iris b/posix-configs/SITL/init/inav/iris index d531b34a16..98ad73dfb9 100644 --- a/posix-configs/SITL/init/inav/iris +++ b/posix-configs/SITL/init/inav/iris @@ -53,7 +53,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/inav/iris_opt_flow b/posix-configs/SITL/init/inav/iris_opt_flow index 7b423d5301..7c249cf5e6 100644 --- a/posix-configs/SITL/init/inav/iris_opt_flow +++ b/posix-configs/SITL/init/inav/iris_opt_flow @@ -56,7 +56,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/lpe/iris b/posix-configs/SITL/init/lpe/iris index 26f4ecc24b..621a24848d 100644 --- a/posix-configs/SITL/init/lpe/iris +++ b/posix-configs/SITL/init/lpe/iris @@ -55,7 +55,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/lpe/iris_opt_flow b/posix-configs/SITL/init/lpe/iris_opt_flow index 178eb1465b..e652bafca4 100644 --- a/posix-configs/SITL/init/lpe/iris_opt_flow +++ b/posix-configs/SITL/init/lpe/iris_opt_flow @@ -73,7 +73,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/lpe/plane b/posix-configs/SITL/init/lpe/plane index 3df84cf36a..6f1c4d5ae2 100644 --- a/posix-configs/SITL/init/lpe/plane +++ b/posix-configs/SITL/init/lpe/plane @@ -60,7 +60,6 @@ adcsim start gpssim start measairspeedsim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start navigator start diff --git a/posix-configs/SITL/init/lpe/solo b/posix-configs/SITL/init/lpe/solo index 09e095d6c7..f168f398e3 100644 --- a/posix-configs/SITL/init/lpe/solo +++ b/posix-configs/SITL/init/lpe/solo @@ -55,7 +55,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/lpe/standard_vtol b/posix-configs/SITL/init/lpe/standard_vtol index 1f3fb8e7c3..e0b49b1734 100644 --- a/posix-configs/SITL/init/lpe/standard_vtol +++ b/posix-configs/SITL/init/lpe/standard_vtol @@ -65,7 +65,6 @@ adcsim start gpssim start measairspeedsim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/lpe/typhoon_h480 b/posix-configs/SITL/init/lpe/typhoon_h480 index ee24ed9a5f..ec432c87f4 100644 --- a/posix-configs/SITL/init/lpe/typhoon_h480 +++ b/posix-configs/SITL/init/lpe/typhoon_h480 @@ -52,7 +52,6 @@ barosim start adcsim start gpssim start pwm_out_sim mode_pwm16 -sleep 1 sensors start commander start land_detector start multicopter diff --git a/posix-configs/SITL/init/rcS_gazebo_delta_wing b/posix-configs/SITL/init/rcS_gazebo_delta_wing index 994fbf5c8e..47223f4627 100644 --- a/posix-configs/SITL/init/rcS_gazebo_delta_wing +++ b/posix-configs/SITL/init/rcS_gazebo_delta_wing @@ -37,7 +37,6 @@ adcsim start gpssim start measairspeedsim start pwm_out_sim mode_pwm -sleep 1 sensors start commander start navigator start