diff --git a/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf b/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf deleted file mode 100644 index c1232f2236..0000000000 --- a/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf +++ /dev/null @@ -1,718 +0,0 @@ - - - - 0 0 0 0 0 0 - - - - 11 - - 0.1 - 0 - 0 - 0.1 - 0 - 0.1 - - - - - - - model://uuv_bluerov2_heavy/meshes/BlueROV2heavy.dae - - - - - - - - - - - - 0 0 0 0 0 0 - - 0 0 0 0 0 0 - 0.015 - - 1e-05 - 0 - 0 - 1e-05 - 0 - 1e-05 - - - - - - - uuv_bluerov2_heavy/imu_link - base_link - - 1 0 0 - - 0 - 0 - 0 - 0 - - - 0 - 0 - - 1 - - - - - - - model://gps - 0 0 0 0 0 0 - gps - - - base_link - gps::link - - - - - - 0.14 -0.10 0 0 1.570796 0.78539815 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster1 - - - - - true - thruster1_joint - thruster1 - ccw - 0.0125 - 0.025 - 1100 - 10 - 0.01 - 0 - 0 - /gazebo/command/motor_speed - 0 - /motor_speed/0 - 0.025 - - - - 0.14 0.10 0 0 1.570796 -0.78539815 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster2 - - - - - true - thruster2_joint - thruster2 - ccw - 0.0125 - 0.025 - 1100 - 10 - 0.01 - 0 - 0 - /gazebo/command/motor_speed - 1 - /motor_speed/1 - 0.025 - - - - -0.14 -0.10 0 0 1.570796 2.356194 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster3 - - - - - true - thruster3_joint - thruster3 - ccw - 0.0125 - 0.025 - 1100 - -10 - -0.01 - 0 - 0 - /gazebo/command/motor_speed - 2 - /motor_speed/2 - 0.025 - - - - -0.14 0.10 0 0 1.570796 -2.356194 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster4 - - - - - true - thruster4_joint - thruster4 - ccw - 0.0125 - 0.025 - 1100 - -10 - -0.01 - 0 - 0 - /gazebo/command/motor_speed - 3 - /motor_speed/3 - 0.025 - - - - 0.12 -0.22 0.06 0 0 0 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster5 - - - - - true - thruster5_joint - thruster5 - ccw - 0.0125 - 0.025 - 1100 - 10 - 0.01 - 0 - 0 - /gazebo/command/motor_speed - 4 - /motor_speed/4 - 0.025 - - - - 0.12 0.22 0.06 0 0 0 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster6 - - - - - true - thruster6_joint - thruster6 - ccw - 0.0125 - 0.025 - 1100 - -10 - -0.01 - 0 - 0 - /gazebo/command/motor_speed - 5 - /motor_speed/5 - 0.025 - - - - - -0.12 -0.22 0.06 0 0 0 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster7 - - - - - true - thruster7_joint - thruster7 - ccw - 0.0125 - 0.025 - 1100 - -10 - -0.01 - 0 - 0 - /gazebo/command/motor_speed - 6 - /motor_speed/6 - 0.025 - - - - -0.12 0.22 0.06 0 0 0 - - 1e-10 - - 1e-06 - 0 - 0 - 1e-06 - 0 - 1e-06 - - - - - - 1 1 1 - model://uuv_bluerov2_heavy/meshes/prop.dae - - - - - - - - - - - 0 0 1 - - -1e+16 - 1e+16 - - - base_link - thruster8 - - - - - true - thruster8_joint - thruster8 - ccw - 0.0125 - 0.025 - 1100 - 10 - 0.01 - 0 - 0 - /gazebo/command/motor_speed - 7 - /motor_speed/7 - 0.025 - - - - - 100 - 0.0004 - 6.4e-06 - 600 - /mag - - - - - - - - - 50 - /baro - - - - - base_link - 1.11 2.8 2.8 - 0.00451 0.0163 0.0163 - 5.39 17.36 17.36 - 0.00114 0.007 0.007 - /gazebo/command/motor_speed - - base_link - 0 0 0 - 1 - 0.05 - - - - - - /imu - /mag - /baro - INADDR_ANY - 14560 - 4560 - 0 - /dev/ttyACM0 - 921600 - INADDR_ANY - 14550 - INADDR_ANY - 14540 - false - false - false - 0 - 1 - true - true - /gazebo/command/motor_speed - - - - - 0 - 0 - 1 - 0 - 0 - velocity - thruster1_joint - - - 1 - 0 - 1 - 0 - 0 - velocity - thruster2_joint - - - 2 - 0 - 1 - 0 - 0 - velocity - thruster3_joint - - - 3 - 0 - 1 - 0 - 0 - velocity - thruster4_joint - - - 4 - 0 - 1 - 0 - 0 - velocity - thruster5_joint - - - 5 - 0 - 1 - 0 - 0 - velocity - thruster6_joint - - - 6 - 0 - 1 - 0 - 0 - velocity - thruster7_joint - - - 7 - 0 - 1 - 0 - 0 - velocity - thruster8_joint - - - - - - - uuv_bluerov2_heavy/imu_link - /imu - 0.0003394 - 3.8785e-05 - 1000.0 - 0.0087 - 0.004 - 0.006 - 300.0 - 0.196 - - - -