diff --git a/submitted_models/marble_qav500_sensor_config_1/launch/spawner.rb b/submitted_models/marble_qav500_sensor_config_1/launch/spawner.rb
index 3640be43..ed6769c0 100755
--- a/submitted_models/marble_qav500_sensor_config_1/launch/spawner.rb
+++ b/submitted_models/marble_qav500_sensor_config_1/launch/spawner.rb
@@ -47,104 +47,105 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
1
- model/#{_name}
- rotor_0_joint
- rotor_0
- ccw
- 0.0182
- 0.0182
- 1000.0
- 1.269e-05
- 0.016754
- command/motor_speed
- 0
- 2.0673e-04
- 0
- motor_speed/0
- 10
- velocity
-
-
- model/#{_name}
- rotor_1_joint
- rotor_1
- cw
- 0.0182
- 0.0182
- 1000.0
- 1.269e-05
- 0.016754
- command/motor_speed
- 1
- 2.0673e-04
- 0
- motor_speed/1
- 10
- velocity
-
-
- model/#{_name}
- rotor_2_joint
- rotor_2
- ccw
- 0.0182
- 0.0182
- 1000.0
- 1.269e-05
- 0.016754
- command/motor_speed
- 2
- 2.0673e-04
- 0
- motor_speed/2
- 10
- velocity
-
-
- model/#{_name}
- rotor_3_joint
- rotor_3
- cw
- 0.0182
- 0.0182
- 1000.0
- 1.269e-05
- 0.016754
- command/motor_speed
- 3
- 2.0673e-04
- 0
- motor_speed/3
- 10
- velocity
-
-
- model/#{_name}
- cmd_vel
- command/motor_speed
- velocity_controller/enable
- base_link
- 8 8 10
- 6 6 6
- 2.5 2.5 4.0
- 5 5 5
- 4 4 4
- 5 5 10
- 0 0 0
-
-
-
- 0.1105 0.1261 0.0947
- 0 0 0
-
-
- 0.004 0.004 0.004
+ name="ignition::gazebo::systems::MulticopterMotorModel">
+ model/#{_name}
+ rotor_0_joint
+ rotor_0
+ ccw
+ 0.0182
+ 0.0182
+ 1000.0
+ 1.269e-05
+ 0.016754
+ command/motor_speed
+ 0
+ 2.0673e-04
+ 0
+ motor_speed/0
+ 10
+ velocity
+
+
+ model/#{_name}
+ rotor_1_joint
+ rotor_1
+ ccw
+ 0.0182
+ 0.0182
+ 1000.0
+ 1.269e-05
+ 0.016754
+ command/motor_speed
+ 1
+ 2.0673e-04
+ 0
+ motor_speed/1
+ 10
+ velocity
+
+
+ model/#{_name}
+ rotor_2_joint
+ rotor_2
+ cw
+ 0.0182
+ 0.0182
+ 1000.0
+ 1.269e-05
+ 0.016754
+ command/motor_speed
+ 2
+ 2.0673e-04
+ 0
+ motor_speed/2
+ 10
+ velocity
+
+
+ model/#{_name}
+ rotor_3_joint
+ rotor_3
+ cw
+ 0.0182
+ 0.0182
+ 1000.0
+ 1.269e-05
+ 0.016754
+ command/motor_speed
+ 3
+ 2.0673e-04
+ 0
+ motor_speed/3
+ 10
+ velocity
+
+
+
+ model/#{_name}
+ cmd_vel
+ command/motor_speed
+ velocity_controller/enable
+ base_link
+ 8 8 10
+ 6 6 6
+ 2.5 2.5 4.0
+ 5 5 3
+ 10 10 5
+ 3 3 6
+ 0 0 0
+
+
+
+ 0.1105 0.1261 0.0947
+ 0 0 0
+
+
+ 0.004 0.004 0.004
@@ -157,13 +158,13 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
rotor_1_joint
1.269e-05
1.6754e-2
- -1
+ 1
rotor_2_joint
1.269e-05
1.6754e-2
- 1
+ -1
rotor_3_joint
diff --git a/submitted_models/marble_qav500_sensor_config_1/launch/vehicle_topics.launch b/submitted_models/marble_qav500_sensor_config_1/launch/vehicle_topics.launch
index 57ce3c6b..afe80cdb 100755
--- a/submitted_models/marble_qav500_sensor_config_1/launch/vehicle_topics.launch
+++ b/submitted_models/marble_qav500_sensor_config_1/launch/vehicle_topics.launch
@@ -102,7 +102,7 @@
type="image_bridge"
name="ros_ign_image_tof_top"
args="$(arg sensor_prefix)/tof_top/depth_image">
-
+
@@ -120,7 +120,7 @@
type="image_bridge"
name="ros_ign_image_tof_bottom"
args="$(arg sensor_prefix)/tof_bottom/depth_image">
-
+
diff --git a/submitted_models/marble_qav500_sensor_config_1/model.sdf b/submitted_models/marble_qav500_sensor_config_1/model.sdf
index 10c094d3..e524fc65 100644
--- a/submitted_models/marble_qav500_sensor_config_1/model.sdf
+++ b/submitted_models/marble_qav500_sensor_config_1/model.sdf
@@ -6,14 +6,21 @@
0 0 0 0 -0 0
0 0 0 0 -0 0
- 3
+
+ 2.06
- 0.03567
+
+ 0.03566
+ 0
+ 0
+ 0.05535
+ 0
+ 0.08475
@@ -587,7 +594,7 @@
-->
- 0.206069 0.206092 0.028 0 0 0.523599
+ 0.206069 -0.205944 0.028 0 0 0.523599
0 0 0 0 -0 0
0.005
@@ -628,7 +635,7 @@
1 0 0 1
@@ -690,13 +697,13 @@
1 1 1
- meshes/neo11_propeller_cw.dae
+ meshes/neo11_propeller_ccw.dae
0 0 1 1
@@ -789,7 +796,7 @@
-->
- -0.206432 -0.205944 0.028 0 -0 -2.61799
+ 0.206432 0.205944 0.028 0 -0 -2.61799
0 0 0 0 -0 0
0.005
@@ -824,7 +831,7 @@
1 1 1
- meshes/neo11_propeller_ccw.dae
+ meshes/neo11_propeller_cw.dae
@@ -923,7 +930,7 @@
-->
- 0.206432 -0.205944 0.028 0 0 -0.523599
+ -0.206432 -0.205944 0.028 0 0 -0.523599
0 0 0 0 -0 0
0.005