It seems that buoyancy is not applied for the robot in the gazebo environment.
I am using the usv urdf file I created to open the gazevo world in the example link above. It seems to be able to load the model into the gazebo world, but there is a problem that the model continues to sink to the bottom. i want to know the solution for this
my urdf code is here:
<?xml version="1.0"?>
<robot name="1kw" xmlns:xacro="http://ros.org/wiki/xacro" >
<xacro:include filename="$(find wamv_gazebo)/urdf/1kw2.gazebo.xacro"/>
<xacro:include filename="$(find wamv_gazebo)/urdf/dynamics/wamv_gazebo_dynamics_plugin.xacro" />
<!-- Define robot constants -->
<xacro:property name="base_W" value="1.5"/>
<xacro:property name="base_D" value="0.09"/>
<xacro:property name="base_H" value="0.03"/>
<xacro:property name="base_M" value="0.08"/>
<xacro:macro name="base_inertia" params="m w d h">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${m}"/>
<inertia ixx="${(m/12) * (d*d)}" ixy = "0" ixz = "0" iyy="${(m/12) * (w*w + d*d)}" iyz = "0" izz="${(m/12) * (w*w)}"/>
</inertial>
</xacro:macro>
<!-- Robot Footprint -->
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.3" rpy="1.570796 0 0"/>
</joint>
<!-- USV Base -->
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://oneusv_urdf/mesh/1kw_ship_body2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.24 0 0.3"/>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://oneusv_urdf/mesh/1kw_ship_body2.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.24 0 0.3"/>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1" ixy="0.0" ixz="0.0" iyy="1" iyz="0.0" izz="1"/>
</inertial>
</link>
<!-- IMU -->
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="0.0 0 0.0" rpy="0 0 0"/>
</joint>
<link name="imu_link"/>
<joint name="lid_joint" type="fixed">
<parent link="base_link"/>
<child link="lid_link"/>
<origin xyz="0.0 0.0 0" rpy="0 0 0"/>
</joint>
<!-- USV lid -->
<link name="lid_link">
<visual>
<geometry>
<mesh filename="package://oneusv_urdf/mesh/1kw_ship_Lid.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.24 0 0.3"/>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://oneusv_urdf/mesh/1kw_ship_Lid.stl" scale="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.24 0 0.3"/>
</collision>
<inertial>
<mass value="1"/>
<inertia ...