diff --git a/models/advanced_plane/model.sdf b/models/advanced_plane/model.sdf index 43af686..39a4539 100644 --- a/models/advanced_plane/model.sdf +++ b/models/advanced_plane/model.sdf @@ -360,9 +360,8 @@ 0 1 0 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -389,9 +388,8 @@ 0 1 0 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -418,9 +416,8 @@ 0 1 0 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -447,9 +444,8 @@ 0 1 0 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -476,9 +472,8 @@ 0 1 0 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -505,9 +500,8 @@ 0 0 1 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 diff --git a/models/lawnmower/model.sdf b/models/lawnmower/model.sdf index 47cfdd1..2cb1766 100644 --- a/models/lawnmower/model.sdf +++ b/models/lawnmower/model.sdf @@ -572,7 +572,6 @@ right_wheel_joint - command/motor_speed true 0 @@ -589,7 +588,6 @@ left_wheel_joint - command/motor_speed true 1 @@ -607,7 +605,7 @@ cutter_blades_joint - servo_2 + servo_0 - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -668,8 +667,8 @@ 0 0 1 - -0.53 - 0.53 + -0.78 + 0.78 1.000 diff --git a/models/standard_vtol/model.sdf b/models/standard_vtol/model.sdf index d99f04a..de678fa 100644 --- a/models/standard_vtol/model.sdf +++ b/models/standard_vtol/model.sdf @@ -598,8 +598,8 @@ 0 1 0 - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -618,8 +618,8 @@ 0 1 0 - -0.53 - 0.53 + -0.78 + 0.78 1.000 @@ -638,9 +638,8 @@ 0 1 0 - - -0.53 - 0.53 + -0.78 + 0.78 1.000 diff --git a/models/tiltrotor/model.config b/models/tiltrotor/model.config new file mode 100644 index 0000000..e1c7d50 --- /dev/null +++ b/models/tiltrotor/model.config @@ -0,0 +1,15 @@ + + + tiltrotor + 1.0 + model.sdf + + + Pernilla Wikström + pernilla@auterion.com + + + + This is a model for a quad-tiltrotor with motors in x configuration. + + diff --git a/models/tiltrotor/model.sdf b/models/tiltrotor/model.sdf new file mode 100644 index 0000000..2a4eee3 --- /dev/null +++ b/models/tiltrotor/model.sdf @@ -0,0 +1,942 @@ + + + + + 0 0 0.246 0 0 0 + + 0 0 0 0 0 0 + + 0 0 0 0 0 0 + 5 + + 0.197563 + 0 + 0 + 0.1458929 + 0 + 0.1477 + + + + -0.01 0 -0.08 0 0 0 + + + 0.55 2.144 0.05 + + + + + + 100000 + 1.0 + 0.1 + 0.001 + + + + + + + + + 0.53 -1.072 -0.1 1.5707963268 0 3.1415926536 + + + 0.001 0.001 0.001 + model://standard_vtol/meshes/x8_wing.dae + + + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 + + + + 0 0.35 0.01 0 0 0 + + + 0.74 0.03 0.03 + + + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 + + + + 0 -0.35 0.01 0 0 0 + + + 0.74 0.03 0.03 + + + + 0.175 0.175 0.175 1.0 + 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 + + + 1 + 250 + + + + + 0 + 0.0003394 + 3.8785e-05 + 1000 + + + + + 0 + 0.0003394 + 3.8785e-05 + 1000 + + + + + 0 + 0.0003394 + 3.8785e-05 + 1000 + + + + + + + 0 + 0.004 + 0.006 + 300 + + + + + 0 + 0.004 + 0.006 + 300 + + + + + 0 + 0.004 + 0.006 + 300 + + + + + + + 1 + 50 + + + + 0 + 0.01 + + + + + + 1 + 30 + + + + + model://airspeed + 0. 0. 0. 0. 0. 0. + + + base_link + airspeed_link + -0 0 0 0 0 0 + + + + 0.35 -0.35 0.045 0 0 0 + + 0 0 0 0 0 0 + 0.05 + + 0.0166704 + 0 + 0 + 0.0166704 + 0 + 0.0167604 + + + + 0 0 0 0 0 0 + + + 0.035 + 0.02 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 0.035 + 0.02 + + + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 + + + 1 + + 0 + + + + motor_0 + base_link + + 0 1 0 + + 0. + 1.57 + + + 1.0 + 0 + 0 + + 1 + + + + + 0.35 -0.35 0.07 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000166704 + 0 + 0.000167604 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.1 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://standard_vtol/meshes/iris_prop_ccw.dae + + + + 0 0 1 1.0 + 0 0 1 1.0 + + + 1 + + 0 + + + rotor_0 + motor_0 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + -0.35 0.35 0.07 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000166704 + 0 + 0.000167604 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.1 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://standard_vtol/meshes/iris_prop_ccw.dae + + + + 0 0 1 1.0 + 0 0 1 1.0 + + + 1 + + 0 + + + rotor_1 + base_link + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + 0.35 0.35 0.045 0 0 0 + + 0 0 0 0 0 0 + 0.05 + + 0.0166704 + 0 + 0 + 0.0166704 + 0 + 0.0167604 + + + + 0 0 0 0 0 0 + + + 0.035 + 0.02 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 0.035 + 0.02 + + + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 + + + 1 + + 0 + + + + motor_2 + base_link + + 0 1 0 + + 0. + 1.57 + + + 1.0 + 0 + 0 + + 1 + + + + + 0.35 0.35 0.07 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000166704 + 0 + 0.000167604 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.1 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://standard_vtol/meshes/iris_prop_cw.dae + + + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 + + + 1 + + 0 + + + rotor_2 + motor_2 + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + -0.35 -0.35 0.07 0 0 0 + + 0 0 0 0 0 0 + 0.005 + + 9.75e-07 + 0 + 0 + 0.000166704 + 0 + 0.000167604 + + + + 0 0 0 0 0 0 + + + 0.005 + 0.1 + + + + + + + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + model://standard_vtol/meshes/iris_prop_cw.dae + + + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 + + + 1 + + 0 + + + rotor_3 + base_link + + 0 0 1 + + -1e+16 + 1e+16 + + + 0 + 0 + + 1 + + + + + + 0.00000001 + + 0.000001 + 0.0 + 0.000001 + 0.0 + 0.0 + 0.000001 + + 0 0.3 0 0.00 0 0.0 + + + -0.105 0.004 -0.034 1.5707963268 0 3.1415926536 + + + 0.001 0.001 0.001 + model://standard_vtol/meshes/x8_elevon_left.dae + + + + 0 0 1 1.0 + 0 0 1 1.0 + + + + + + 0.00000001 + + 0.000001 + 0.0 + 0.000001 + 0.0 + 0.0 + 0.000001 + + 0 -0.6 0 0.00 0 0.0 + + + 0.281 -1.032 -0.034 1.5707963268 0 3.1415926536 + + + 0.001 0.001 0.001 + model://standard_vtol/meshes/x8_elevon_right.dae + + + + 0 0 1 1.0 + 0 0 1 1.0 + + + + + + 0.00000001 + + 0.000001 + 0.0 + 0.000001 + 0.0 + 0.0 + 0.000001 + + -0.5 0 0 0.00 0 0.0 + + + + + 0.00000001 + + 0.000001 + 0.0 + 0.000001 + 0.0 + 0.0 + 0.000001 + + -0.5 0 0.05 0 0 0 + + + + base_link + left_elevon + -0.18 0.6 -0.005 0 0 0.265 + + 0 1 0 + + -0.78 + 0.78 + + + 1.000 + + + + + 1 + + + + + base_link + right_elevon + -0.18 -0.6 -0.005 0 0 -0.265 + + 0 1 0 + + -0.78 + 0.78 + + + 1.000 + + + + + 1 + + + + + base_link + elevator + -0.5 0 0 0 0 0 + + 0 1 0 + + -0.78 + 0.78 + + + 1.000 + + + + + 1 + + + + + base_link + rudder + -0.5 0 0.05 0.00 0 0.0 + + 1 0 0 + + + -0.01 + 0.01 + + + 1.000 + + + + + 1 + + + + + 0.05984281113 + 4.752798721 + 0.6417112299 + 0.0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.05 0.3 0.05 + 0.5 + 1.2041 + 1 0 0 + 0 0 1 + base_link + + left_elevon_joint + + -1.0 + + + left_elevon_joint + servo_0 + + + 0.05984281113 + 4.752798721 + 0.6417112299 + 0.0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.05 -0.3 0.05 + 0.5 + 1.2041 + 1 0 0 + 0 0 1 + base_link + + right_elevon_joint + + -1.0 + + + right_elevon_joint + servo_1 + + + -0.2 + 4.752798721 + 0.6417112299 + 0.0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.5 0 0 + 0.01 + 1.2041 + 1 0 0 + 0 0 1 + base_link + + elevator_joint + + -12.0 + + + elevator_joint + servo_2 + + + 0.0 + 4.752798721 + 0.6417112299 + 0.0 + 0.3391428111 + -3.85 + -0.9233984055 + 0 + -0.5 0 0.05 + 0.02 + 1.2041 + 1 0 0 + 0 1 0 + base_link + + + + + rotor_0_joint + rotor_0 + ccw + 0.0125 + 0.025 + 1500 + 2e-05 + 0.06 + command/motor_speed + 0 + 0.0000806428 + 1e-06 + 20 + velocity + + + motor_0_joint + servo_3 + 100 + 0 + 0 + 0.0 + 0.0 + 2 + -2 + 0.2 + + + rotor_1_joint + rotor_1 + ccw + 0.0125 + 0.025 + 1500 + 2e-05 + 0.06 + command/motor_speed + 1 + 0.0000806428 + 1e-06 + 20 + velocity + + + rotor_2_joint + rotor_2 + cw + 0.0125 + 0.025 + 1500 + 2e-05 + 0.06 + command/motor_speed + 2 + 0.0000806428 + 1e-06 + 20 + velocity + + + motor_2_joint + servo_4 + 100 + 0 + 0 + 0.0 + 0.0 + 2 + -2 + 0.2 + + + rotor_3_joint + rotor_3 + cw + 0.0125 + 0.025 + 1500 + 2e-05 + 0.06 + command/motor_speed + 3 + 0.0000806428 + 1e-06 + 20 + velocity + + 0 + +