From 2cdb57239609f5b4ea0f4ef5ab5015ea398bc0cc Mon Sep 17 00:00:00 2001 From: Matteo Del Seppia <71389092+matteodelseppia@users.noreply.github.com> Date: Thu, 30 May 2024 17:36:07 +0200 Subject: [PATCH 1/3] Adding IMU link and joint to uuv_bluerov2_heavy Adding the iMU link and joint the uuv_bluerov2_heavy model, since it is currently unusable. --- .../uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf | 87 ++++++++++++++----- 1 file changed, 64 insertions(+), 23 deletions(-) diff --git a/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf b/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf index e99e8199a1..c1232f2236 100644 --- a/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf +++ b/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf @@ -1,6 +1,6 @@ - + 0 0 0 0 0 0 @@ -30,22 +30,59 @@ + + + + 0 0 0 0 0 0 + + 0 0 0 0 0 0 + 0.015 + + 1e-05 + 0 + 0 + 1e-05 + 0 + 1e-05 + + + - - - model://gps - 0 0 0 0 0 0 - gps - - - base_link - gps::link - + + 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 @@ -526,18 +563,22 @@ /motor_speed/7 0.025 - - - + + + 100 0.0004 6.4e-06 600 /mag - - - + + + + + + + 50 /baro @@ -577,7 +618,7 @@ false false 0 - 0 + 1 true true /gazebo/command/motor_speed @@ -658,10 +699,10 @@ - - - - base_link + + + + uuv_bluerov2_heavy/imu_link /imu 0.0003394 3.8785e-05 From 62d8f771e2426de5591b86a29d5c04e6304924e2 Mon Sep 17 00:00:00 2001 From: Matteo Del Seppia <71389092+matteodelseppia@users.noreply.github.com> Date: Thu, 30 May 2024 17:39:03 +0200 Subject: [PATCH 2/3] Adding uuv_bluerov2_heavy.sdf.jinja for multi vehicle UUV simulations --- .../uuv_bluerov2_heavy.sdf.jinja | 718 ++++++++++++++++++ 1 file changed, 718 insertions(+) create mode 100644 models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf.jinja diff --git a/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf.jinja b/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf.jinja new file mode 100644 index 0000000000..794320870c --- /dev/null +++ b/models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf.jinja @@ -0,0 +1,718 @@ + + + + 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 + {{ mavlink_udp_port }} + {{ mavlink_tcp_port }} + {{ serial_enabled }} + {{ serial_device }} + {{ serial_baudrate }} + INADDR_ANY + 14550 + INADDR_ANY + 14540 + {{ hil_mode }} + 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 + + + + From e8b1e0f9a91d74aed773c59ac7deb51fdd79d891 Mon Sep 17 00:00:00 2001 From: Matteo Del Seppia <71389092+matteodelseppia@users.noreply.github.com> Date: Fri, 31 May 2024 00:01:05 +0200 Subject: [PATCH 3/3] Delete models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf Deleting the SDF model in favor of the jinja template --- .../uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf | 718 ------------------ 1 file changed, 718 deletions(-) delete mode 100644 models/uuv_bluerov2_heavy/uuv_bluerov2_heavy.sdf 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 - - - -