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

Support SITL simulation for boat with usv_gazebo plugin #357

Closed
wants to merge 3 commits into from
Closed
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
381 changes: 381 additions & 0 deletions models/boat/boat.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,381 @@
<?xml version="1.0"?>
<sdf version='1.5'>
<model name='boat'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<!-- From WAM-V spec sheet -->
<mass>180.0</mass>
<inertia>
<ixx>120</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>393</iyy>
<iyz>0</iyz>
<izz>446.0</izz>
</inertia>
</inertial>
<collision name='base_link_collision'>
<pose>0 0 -0.07 0 0 0</pose>
<geometry>
<box>
<size>0.47 0.47 0.11</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<max_vel>10</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
<!--<friction>
<ode/>
</friction>-->
</surface>
</collision>
<collision name='left_float'>
<pose>0.4 1.03 0.2 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.2</radius>
<length>4.0</length>
</cylinder>
</geometry>
</collision>
<collision name='right_float'>
<pose>0.4 -1.03 0.2 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.2</radius>
<length>4.0</length>
</cylinder>
</geometry>
</collision>
<collision name='left_mid_float'>
<pose>1.85 1.03 0.3 0 1.38 0</pose>
<geometry>
<cylinder>
<radius>0.17</radius>
<length>0.5</length>
</cylinder>
</geometry>
</collision>
<collision name='right_mid_float'>
<pose>1.85 -1.03 0.3 0 1.38 0</pose>
<geometry>
<cylinder>
<radius>0.17</radius>
<length>0.5</length>
</cylinder>
</geometry>
</collision>
<collision name='left_front_float'>
<pose>2.3 -1.03 0.4 0 1.3 0</pose>
<geometry>
<cylinder>
<radius>0.12</radius>
<length>0.45</length>
</cylinder>
</geometry>
</collision>
<collision name='right_front_float'>
<pose>2.3 -1.03 0.4 0 1.3 0</pose>
<geometry>
<cylinder>
<radius>0.12</radius>
<length>0.45</length>
</cylinder>
</geometry>
</collision>
<visual name='base_link_visual'>
<pose>0.07 0 -0.08 0 0.0 0</pose>
<geometry>
<mesh>
<scale>1.0 1.0 1.0</scale>
<uri>model://boat/meshes/body.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>0</self_collide>
</link>
<link name='boat/imu_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
</link>
<link name='boat/left_engine_link'>
<pose>-2.373776 1.027135 0.318237 0 0 0</pose>
<visual name='left_engine_link_visual'>
<geometry>
<mesh>
<scale>1.0 1.0 1.0</scale>
<uri>model://boat/meshes/engine.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='left_engine_vertical_axis_collision'>
<pose>-0.16 0 -0.24 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.15 0.83</size>
</box>
</geometry>
</collision>
<collision name='left_engine_rear_end_collision'>
<pose>-0.34 0 0.12 0 0 0</pose>
<geometry>
<box>
<size>0.12 0.15 0.12</size>
</box>
</geometry>
</collision>
<inertial>
<mass>15</mass>
<inertia>
<ixx>0.889245</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.911125</iyy>
<iyz>0</iyz>
<izz>0.078125</izz>
</inertia>
</inertial>
</link>
<link name='boat/left_propeller_link'>
<pose>-2.651932 1.027135 -0.191134 0 0 0</pose>
<visual name='left_propeller_link_visual'>
<geometry>
<mesh>
<scale>1.0 1.0 1.0</scale>
<uri>model://boat/meshes/propeller.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Blue</name>
<uri>__default__</uri>
</script>
</material>
</visual>
<collision name='left_propeller_collision'>
<pose>-0.08 0 0 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.24</radius>
<length>0.18</length>
</cylinder>
</geometry>
</collision>
<inertial>
<mass>0.5</mass>
<inertia>
<ixx>0.008545</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.008545</iyy>
<iyz>0</iyz>
<izz>0.0144</izz>
</inertia>
</inertial>
</link>
<joint name='boat/imu_joint' type='revolute'>
<child>boat/imu_link</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<joint name='boat/left_chasis_engine_joint' type='revolute'>
<child>boat/left_engine_link</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-3.14</lower>
<upper>3.14</upper>
<effort>10</effort>
<velocity>10</velocity>
</limit>
</axis>
</joint>
<joint name='boat/left_engine_propeller_joint' type='revolute'>
<child>boat/left_propeller_link</child>
<parent>boat/left_engine_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<effort>100</effort>
<velocity>100</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<friction>0.05</friction>
<damping>0.05</damping>
</dynamics>
</axis>
<use_parent_model_frame>1</use_parent_model_frame>
</joint>
<plugin name="usv_dynamics" filename="libusv_gazebo_dynamics_plugin.so">
<bodyName>base_link</bodyName>
<!-- Must be same as the ocean model!-->
<waterLevel>0</waterLevel>
<waterDensity>997.8</waterDensity>
<!-- Added mass -->
<xDotU>0.0</xDotU>
<yDotV>0.0</yDotV>
<nDotR>0.0</nDotR>
<!-- Linear and quadratic drag -->
<xU>51.3</xU>
<xUU>72.4</xUU>
<yV>40.0</yV>
<yVV>0.0</yVV>
<zW>500.0</zW>
<kP>50.0</kP>
<mQ>50.0</mQ>
<nR>400.0</nR>
<nRR>0.0</nRR>
<!-- General dimensions -->
<!--<boatArea>2.2</boatArea>-->
<hullRadius>0.213</hullRadius>
<boatWidth>2.4</boatWidth>
<boatLength>4.9</boatLength>
<!-- Length discretization, AKA, "N" -->
<length_n>2</length_n>
<!-- Wave model -->
<wave_model>ocean_waves</wave_model>
</plugin>
<plugin name="wamv_gazebo_thrust" filename="libusv_gazebo_thrust_plugin.so">
<cmdTimeout>1.0</cmdTimeout>
<thruster>
<!-- Required Parameters -->
<linkName>boat/left_propeller_link</linkName>
<propJointName>boat/left_engine_propeller_joint</propJointName>
<engineJointName>boat/left_chasis_engine_joint</engineJointName>
<cmdTopic>/gazebo/command/motor_speed</cmdTopic>
<angleTopic>left_thrust_angle</angleTopic>
<enableAngle>true</enableAngle>
<!-- Optional Parameters -->
<mappingType>1</mappingType>
<maxCmd>1.0</maxCmd>
<maxForceFwd>250.0</maxForceFwd>
<maxForceRev>-100.0</maxForceRev>
<maxAngle>1.57</maxAngle>
</thruster>
<!-- <thruster> -->
<!-- Required Parameters -->
<!-- <linkName>right_propeller_link</linkName>
<propJointName>right_engine_propeller_joint</propJointName>
<engineJointName>right_chasis_engine_joint</engineJointName>
<cmdTopic>right_thrust_cmd</cmdTopic>
<angleTopic>right_thrust_angle</angleTopic>
<enableAngle>true</enableAngle>
-->
<!-- Optional Parameters -->
<!-- <mappingType>1</mappingType>
<maxCmd>1.0</maxCmd>
<maxForceFwd>250.0</maxForceFwd>
<maxForceRev>-100.0</maxForceRev>
<maxAngle>1.57</maxAngle>
</thruster>
--> </plugin>
<plugin name='gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
<robotNamespace></robotNamespace>
<linkName>boat/imu_link</linkName>
<imuTopic>/imu</imuTopic>
<gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
<gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
<gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
<gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
<accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
<accelerometerRandomWalk>0.006</accelerometerRandomWalk>
<accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
<accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
</plugin>
<plugin name="gps_plugin" filename="libgazebo_gps_plugin.so">
<robotNamespace></robotNamespace>
<gpsNoise>true</gpsNoise>
</plugin>
<plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
<robotNamespace/>
<pubRate>20</pubRate>
<noiseDensity>0.0004</noiseDensity>
<randomWalk>6.4e-06</randomWalk>
<biasCorrelationTime>600</biasCorrelationTime>
<magTopic>/mag</magTopic>
</plugin>
<plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
<robotNamespace/>
<pubRate>10</pubRate>
<baroTopic>/baro</baroTopic>
</plugin>
<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
<robotNamespace></robotNamespace>
<imuSubTopic>/imu</imuSubTopic>
<gpsSubTopic>/gps</gpsSubTopic>
<magSubTopic>/mag</magSubTopic>
<baroSubTopic>/baro</baroSubTopic>
<mavlink_addr>INADDR_ANY</mavlink_addr>
<mavlink_udp_port>14560</mavlink_udp_port>
<serialEnabled>false</serialEnabled>
<serialDevice>/dev/ttyACM0</serialDevice>
<baudRate>921600</baudRate>
<qgc_addr>INADDR_ANY</qgc_addr>
<qgc_udp_port>14550</qgc_udp_port>
<sdk_addr>INADDR_ANY</sdk_addr>
<sdk_udp_port>14540</sdk_udp_port>
<hil_mode>false</hil_mode>
<hil_state_level>false</hil_state_level>
<enable_lockstep>true</enable_lockstep>
<use_tcp>true</use_tcp>
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
<control_channels>
<channel name="left_propeller_drive">
<input_index>5</input_index>
<input_offset>0</input_offset>
<input_scaling>40</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_name>boat/left_engine_propeller_joint</joint_name>
<joint_control_pid>
<p>50</p>
<i>20</i>
<d>2</d>
<iMax>800</iMax>
<iMin>-800</iMin>
<cmdMax>1200</cmdMax>
<cmdMin>-1200</cmdMin>
</joint_control_pid>
</channel>
</control_channels>
</plugin>
<static>0</static>
</model>
</sdf>
Binary file added models/boat/meshes/WamV.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading