diff --git a/models/tiltrotor/model.sdf b/models/tiltrotor/model.sdf index ab323ae..619fc9c 100644 --- a/models/tiltrotor/model.sdf +++ b/models/tiltrotor/model.sdf @@ -1,3 +1,4 @@ + @@ -45,11 +46,9 @@ model://tiltrotor/meshes/x8_wing.dae - - + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 @@ -59,11 +58,9 @@ 0.74 0.03 0.03 - - + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 @@ -73,59 +70,101 @@ 0.74 0.03 0.03 - - + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.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 + - - 0 0 0 0 0 0 - - 0 0 0 0 0 0 - 0.015 - - 1e-05 - 0 - 0 - 1e-05 - 0 - 1e-05 - - - - - tiltrotor/imu_link - base_link - - 1 0 0 - - 0 - 0 - 0 - 0 - - - 0 - 0 - - 1 - - - + + model://airspeed - 0 0 0 0 0 0 - airspeed + 0. 0. 0. 0. 0. 0. - airspeed::link base_link + airspeed_link + -0 0 0 0 0 0 + 0.35 -0.35 0.02 0 0 0 @@ -166,10 +205,8 @@ - + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 1 @@ -235,11 +272,9 @@ model://tiltrotor/meshes/iris_prop_ccw.dae - - + + 0 0 1 1.0 + 0 0 1 1.0 1 @@ -302,11 +337,9 @@ model://tiltrotor/meshes/iris_prop_ccw.dae - - + + 0 0 1 1.0 + 0 0 1 1.0 1 @@ -330,8 +363,6 @@ - - 0.35 0.35 0.02 0 0 0 @@ -372,10 +403,8 @@ - + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 1 @@ -441,11 +470,9 @@ model://tiltrotor/meshes/iris_prop_ccw.dae - - + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 1 @@ -508,11 +535,9 @@ model://tiltrotor/meshes/iris_prop_ccw.dae - - + + 0.175 0.175 0.175 1.0 + 0.175 0.175 0.175 1.0 1 @@ -557,11 +582,9 @@ model://tiltrotor/meshes/x8_elevon_left.dae - - + + 0 0 1 1.0 + 0 0 1 1.0 @@ -586,11 +609,9 @@ model://tiltrotor/meshes/x8_elevon_right.dae - - + + 0 0 1 1.0 + 0 0 1 1.0 @@ -706,16 +727,7 @@ - - model://gps - 0 0 0 0 0 0 - gps - - - gps::link - base_link - - + 0.05984281113 4.752798721 0.6417112299 @@ -734,10 +746,13 @@ left_elevon_joint -1.0 - - world_wind - + + left_elevon_joint + servo_0 + + 0.05984281113 4.752798721 0.6417112299 @@ -756,10 +771,13 @@ right_elevon_joint -1.0 - - world_wind - + + right_elevon_joint + servo_1 + + -0.2 4.752798721 0.6417112299 @@ -778,10 +796,13 @@ elevator_joint -12.0 - - world_wind - + + elevator_joint + servo_2 + + 0.0 4.752798721 0.6417112299 @@ -796,11 +817,16 @@ 1 0 0 0 1 0 base_link - - world_wind + - - + + rotor_0_joint rotor_0 ccw @@ -809,15 +835,28 @@ 1500 2e-05 0.06 - /gazebo/command/motor_speed + command/motor_speed 0 0.0000806428 1e-06 - /motor_speed/0 20 + velocity + + + motor_0_joint + servo_3 + position + 10 + 0 + 0 + 0.0 + 0.0 + 2 + -2 + 0.2 - - + rotor_1_joint rotor_1 ccw @@ -826,15 +865,14 @@ 1500 2e-05 0.06 - /gazebo/command/motor_speed + command/motor_speed 1 0.0000806428 1e-06 - /motor_speed/1 20 + velocity - - + rotor_2_joint rotor_2 cw @@ -843,15 +881,28 @@ 1500 2e-05 0.06 - /gazebo/command/motor_speed + command/motor_speed 2 0.0000806428 1e-06 - /motor_speed/2 20 + velocity - - + + motor_2_joint + servo_4 + position + 10 + 0 + 0 + 0.0 + 0.0 + 2 + -2 + 0.2 + + rotor_3_joint rotor_3 cw @@ -860,165 +911,12 @@ 1500 2e-05 0.06 - /gazebo/command/motor_speed + command/motor_speed 3 0.0000806428 1e-06 - /motor_speed/3 20 - - - - tiltrotor/imu_link - /imu - 0.0003394 - 3.8785e-05 - 1000.0 - 0.0087 - 0.004 - 0.006 - 300.0 - 0.196 - - - - - - - 100 - 0.0004 - 6.4e-06 - 600 - /mag - - - - 50 - /baro - - - - /imu - /mag - /baro - INADDR_ANY - {{ mavlink_tcp_port }} - {{ mavlink_udp_port }} - false - /dev/ttyACM0 - 921600 - INADDR_ANY - 14550 - INADDR_ANY - 14540 - false - false - true - true - /gazebo/command/motor_speed - - - 0 - 0 - 1500 - 0 - 0 - velocity - rotor_0_joint - - - 1 - 0 - 1500 - 0 - 0 - velocity - rotor_1_joint - - - 2 - 0 - 1500 - 0 - 0 - velocity - rotor_2_joint - - - 3 - 0 - 1500 - 0 - 0 - velocity - rotor_3_joint - - - 4 - 0.785398 - 0.785398 - 0 - 0 - position - motor_0_joint - -

10

- 0 - 0 - 0.0 - 0.0 - 2 - -2 - 0.2 -
-
- - 5 - 0.785398 - 0.785398 - 0 - 0 - position - motor_2_joint - -

10

- 0 - 0 - 0.0 - 0.0 - 2 - -2 - 0.2 -
-
- - 6 - 0 - 1 - 0 - 0 - position_kinematic - left_elevon_joint - - - 7 - 0 - 1 - 0 - 0 - position_kinematic - right_elevon_joint - - - 8 - 0 - 1 - 0 - 0 - position_kinematic - elevator_joint - -
+ velocity
0