diff --git a/models/tiltrotor/model.sdf b/models/tiltrotor/model.sdf index 619fc9c..e7d7047 100644 --- a/models/tiltrotor/model.sdf +++ b/models/tiltrotor/model.sdf @@ -75,6 +75,32 @@ 0.175 0.175 0.175 1.0 + + -0.35 -0.35 0.045 0 0 0 + + + 0.035 + 0.02 + + + + .175 .175 .175 1.0 + .175 .175 .175 1.0 + + + + -0.35 0.35 0.045 0 0 0 + + + 0.035 + 0.02 + + + + .175 .175 .175 1.0 + .175 .175 .175 1.0 + + 1 0 @@ -166,7 +192,7 @@ - 0.35 -0.35 0.02 0 0 0 + 0.35 -0.35 0.045 0 0 0 0 0 0 0 0 0 0.05 @@ -220,8 +246,8 @@ 0 1 0 - -1.5 - 1.5 + 0. + 1.57 1.0 @@ -232,7 +258,6 @@ - 0.35 -0.35 0.07 0 0 0 @@ -364,7 +389,7 @@ - 0.35 0.35 0.02 0 0 0 + 0.35 0.35 0.045 0 0 0 0 0 0 0 0 0 0.05 @@ -418,8 +443,8 @@ 0 1 0 - -1.5 - 1.5 + 0. + 1.57 1.0 @@ -430,7 +455,6 @@ - 0.35 0.35 0.07 0 0 0 @@ -467,7 +491,7 @@ 1 1 1 - model://tiltrotor/meshes/iris_prop_ccw.dae + model://tiltrotor/meshes/iris_prop_cw.dae @@ -532,7 +556,7 @@ 1 1 1 - model://tiltrotor/meshes/iris_prop_ccw.dae + model://tiltrotor/meshes/iris_prop_cw.dae @@ -846,7 +870,6 @@ filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController"> motor_0_joint servo_3 - position 10 0 0 @@ -892,7 +915,6 @@ filename="gz-sim-joint-position-controller-system" name="gz::sim::systems::JointPositionController"> motor_2_joint servo_4 - position 10 0 0