Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add omnidirectional boat model and ocean world #36

Draft
wants to merge 10 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions models/r1_rover/model.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<sdf version='1.6'>
<model name='r1_rover'>
<model name='r1_rover'>
<link name='base_link'>
<pose>0 0 0 0 -0 0</pose>
<inertial>
Expand Down Expand Up @@ -221,7 +221,7 @@
</axis>
</joint>
<link name='lb_wheel_link'>
pose>-0.15 0.16317 0.0215 0 -0 0</pose>
<pose>-0.15 0.16317 0.0215 0 -0 0</pose>
<inertial>
<pose>0 0 0 1.57079632679 0 0</pose>
<mass>0.414</mass>
Expand Down Expand Up @@ -319,7 +319,7 @@
</inertia>
</inertial>
<collision name='rf_wheel_link_collision'>
pose>0 0 0 1.57079632679 0 0</pose>
<pose>0 0 0 1.57079632679 0 0</pose>
<geometry>
<cylinder>
<radius>0.0686</radius>
Expand Down
Binary file added models/sese_omni_boat/meshes/ASV_RYBITWA.stl
Binary file not shown.
69 changes: 69 additions & 0 deletions models/sese_omni_boat/meshes/prop.dae

Large diffs are not rendered by default.

17 changes: 17 additions & 0 deletions models/sese_omni_boat/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>

<model>
<name>SeSe Omni Boat</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>

<author>
<name>TODO</name>
<email>TODO</email>
</author>

<description>
Modified model of the BlueROV2 4 thrusters. TODO
</description>

</model>
323 changes: 323 additions & 0 deletions models/sese_omni_boat/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,323 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name="sese_omni_boat">
<pose>0 0 0 0 0 0</pose>
<self_collide>false</self_collide>
<static>false</static>
<link name="base_link">
<velocity_decay />
<inertial>
<mass>30</mass>
<inertia>
<ixx>3.78</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1.65</iyy>
<iyz>0</iyz>
<izz>4.53</izz>
</inertia>
</inertial>
<visual name="base_link_visual">
<pose>0 0 0 0 0 -1.57</pose>
<geometry>
<mesh>
<uri>model://sese_omni_boat/meshes/ASV_RYBITWA.stl</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.2 0.2 0.2 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</material>
</visual>
<collision name="base_link_collision_1">
<pose>0 0 0.1 0 0 0</pose>
<geometry>
<box>
<size>0.55 1.3 0.37</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode />
</friction>
</surface>
</collision>
<sensor name="air_pressure_sensor" type="air_pressure">
<always_on>1</always_on>
<update_rate>50</update_rate>
<air_pressure>
<pressure>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</pressure>
</air_pressure>
</sensor>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>250</update_rate>
</sensor>
<sensor name="navsat_sensor" type="navsat">
<always_on>1</always_on>
<update_rate>30</update_rate>
</sensor>
</link>


<link
name="thruster1">
<velocity_decay />
<pose>-0.225 0.4 -0.19 0 0 -0.785</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 -1.571 0 0</pose>
<geometry>
<mesh>
<uri>meshes/prop.dae</uri>
</mesh>
</geometry>
<material>
<!-- Blue for clockwise -->
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
<inertial>
<mass>0.002</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
</link>
<link
name="thruster2">
<velocity_decay />
<pose>0.225 0.4 -0.19 0 0 0.785</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 -1.571 0 0</pose>
<geometry>
<mesh>
<uri>meshes/prop.dae</uri>
</mesh>
</geometry>
<material>
<!-- Green for counterclockwise -->
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
<inertial>
<mass>0.002</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
</link>
<link
name="thruster3">
<velocity_decay />
<pose>-0.225 -0.4 -0.19 0 0 0.785</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 1.571 0 0</pose>
<geometry>
<mesh>
<uri>meshes/prop.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
<inertial>
<mass>0.002</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
</link>
<link
name="thruster4">
<velocity_decay />
<pose>0.225 -0.4 -0.19 0 0 -0.785</pose>
<visual name="thruster_prop_visual">
<pose>0 0 0 1.571 0 0</pose>
<geometry>
<mesh>
<uri>meshes/prop.dae</uri>
</mesh>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
<inertial>
<mass>0.002</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
</link>

<joint
name="thruster1_joint" type="revolute">
<parent>base_link</parent>
<child>thruster1</child>
<axis>
<xyz>0 0 -1</xyz>
</axis>
</joint>
<joint name="thruster2_joint"
type="revolute">
<parent>base_link</parent>
<child>thruster2</child>
<axis>
<xyz>0 0 -1</xyz>
</axis>
</joint>
<joint name="thruster3_joint"
type="revolute">
<parent>base_link</parent>
<child>thruster3</child>
<axis>
<xyz>0 0 -1</xyz>
</axis>
</joint>
<joint name="thruster4_joint"
type="revolute">
<parent>base_link</parent>
<child>thruster4</child>
<axis>
<xyz>0 0 -1</xyz>
</axis>
</joint>

<plugin
filename="gz-sim-thruster-system"
name="gz::sim::systems::Thruster">
<namespace>sese_omni_boat</namespace>
<joint_name>thruster1_joint</joint_name>
<thrust_coefficient>0.02</thrust_coefficient>
<fluid_density>1000.0</fluid_density>
<propeller_diameter>0.1</propeller_diameter>
<velocity_control>true</velocity_control>
<use_angvel_cmd>False</use_angvel_cmd>
</plugin>
<plugin
filename="gz-sim-thruster-system"
name="gz::sim::systems::Thruster">
<namespace>sese_omni_boat</namespace>
<joint_name>thruster2_joint</joint_name>
<thrust_coefficient>0.02</thrust_coefficient>
<fluid_density>1000.0</fluid_density>
<propeller_diameter>0.1</propeller_diameter>
<velocity_control>true</velocity_control>
<use_angvel_cmd>False</use_angvel_cmd>
</plugin>
<plugin
filename="gz-sim-thruster-system"
name="gz::sim::systems::Thruster">
<namespace>sese_omni_boat</namespace>
<joint_name>thruster3_joint</joint_name>
<thrust_coefficient>-0.02</thrust_coefficient>
<fluid_density>
1000.0</fluid_density>
<propeller_diameter>0.1</propeller_diameter>
<velocity_control>true</velocity_control>
<use_angvel_cmd>
False</use_angvel_cmd>
</plugin>
<plugin
filename="gz-sim-thruster-system"
name="gz::sim::systems::Thruster">
<namespace>sese_omni_boat</namespace>
<joint_name>thruster4_joint</joint_name>
<thrust_coefficient>-0.02</thrust_coefficient>
<fluid_density>1000.0</fluid_density>
<propeller_diameter>0.1</propeller_diameter>
<velocity_control>true</velocity_control>
<use_angvel_cmd>False</use_angvel_cmd>
</plugin>

<plugin
filename="ignition-gazebo-pose-publisher-system"
name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>false</publish_link_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_sensor_pose>false</publish_sensor_pose>
<publish_nested_model_pose>true</publish_nested_model_pose>
<update_frequency>20</update_frequency>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>thruster1_joint</joint_name>
<p_gain>0.1</p_gain>
</plugin>

<!-- <plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>vertical_fins_joint</joint_name>
<p_gain>0.1</p_gain>
</plugin> -->

<plugin
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-0.04876161</xDotU>
<yDotV>-1.26324739</yDotV>
<zDotW>-1.26324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-0.3346</mDotQ>
<nDotR>-0.3346</nDotR>
<xUabsU>-0.62282</xUabsU>
<xU>-5</xU>
<yVabsV>-60.127</yVabsV>
<yV>-5</yV>
<zWabsW>-6.0127</zWabsW>
<zW>-100</zW>
<kPabsP>-0.001916</kPabsP>
<kP>-1</kP>
<mQabsQ>-6.32698957</mQabsQ>
<mQ>-1</mQ>
<nRabsR>-6.32698957</nRabsR>
<nR>-1</nR>
</plugin>
</model>
</sdf>
Loading