Skip to content

Commit

Permalink
✨ add simulation launch
Browse files Browse the repository at this point in the history
  • Loading branch information
Rezenders committed Jan 28, 2023
1 parent 19b1be3 commit 75b2fa7
Show file tree
Hide file tree
Showing 4 changed files with 163 additions and 3 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@ project(bluerov2_ignition)
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

ament_auto_package(INSTALL_TO_SHARE models worlds)
ament_auto_package(INSTALL_TO_SHARE launch models worlds)
115 changes: 115 additions & 0 deletions launch/simulation.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration


def generate_launch_description():
pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim')
bluerov2_ignition_path = get_package_share_directory('bluerov2_ignition')
world_path = os.path.join(
bluerov2_ignition_path, 'worlds', 'underwater_minimal.world')
sand_path = os.path.join(
bluerov2_ignition_path, 'models', 'sand_heightmap')
axes_path = os.path.join(
bluerov2_ignition_path, 'models', 'axes')
bluerov2_path = os.path.join(
bluerov2_ignition_path, 'models', 'bluerov2')

underwater_world = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')),
launch_arguments={
'gz_args': '-r ' + world_path
}.items(),
)

x = LaunchConfiguration('x')
y = LaunchConfiguration('y')
z = LaunchConfiguration('z')
x_arg = DeclareLaunchArgument(
'x',
default_value='0.0',
description='Initial x coordinate for bluerov2'
)

y_arg = DeclareLaunchArgument(
'y',
default_value='0.0',
description='Initial y coordinate for bluerov2'
)

z_arg = DeclareLaunchArgument(
'z',
default_value='-1.5',
description='Initial z coordinate for bluerov2'
)

gz_bluerov_pose_bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=['/model/bluerov2/pose@geometry_msgs/msg/Pose@gz.msgs.Pose'],
output='screen',
name='gz_bluerov_pose_bridge',
)

bluerov_spawn = Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-v4',
'-g',
'-world', 'underwater',
'-file', bluerov2_path,
'-name', 'bluerov2',
'-x', x,
'-y', y,
'-z', z,
'-Y', '0']
)

sand_spawn = Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-v4',
'-g',
'-world', 'underwater',
'-file', sand_path,
'-name', 'sand',
'-x', '0.0',
'-y', '7.0',
'-z', '-10.0',
'-Y', '0']
)
axes_spawn = Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-v4',
'-g',
'-world', 'underwater',
'-file', axes_path,
'-name', 'axes',
'-x', '0.0',
'-y', '0.0',
'-z', '0.2',
'-Y', '0']
)

return LaunchDescription([
x_arg,
y_arg,
z_arg,
underwater_world,
bluerov_spawn,
sand_spawn,
axes_spawn,
gz_bluerov_pose_bridge,
])
4 changes: 2 additions & 2 deletions models/sand_heightmap/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<geometry>
<mesh>
<scale>0.5 0.5 0.25</scale>
<uri>model://sand_heightmap/meshes/sandseabed.dae</uri>
<uri>meshes/sandseabed.dae</uri>
</mesh>
</geometry>
</collision>
Expand All @@ -33,7 +33,7 @@
<geometry>
<mesh>
<scale>0.5 0.5 0.25</scale>
<uri>model://sand_heightmap/meshes/sandseabed.dae</uri>
<uri>meshes/sandseabed.dae</uri>
</mesh>
</geometry>
<material>
Expand Down
45 changes: 45 additions & 0 deletions worlds/underwater_minimal.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="underwater">

<!-- Base Gazebo plugins -->
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>

<!-- IMU plugin manages all IMU sensors -->
<plugin filename="libgz-sim-imu-system.so"
name="gz::sim::systems::Imu">
</plugin>

<!-- Buoyancy plugin manages buoyancy for all models -->
<plugin
filename="gz-sim-buoyancy-system"
name="gz::sim::systems::Buoyancy">
<!-- Fluid density is 1 (air) above 0 and 1000 (water) below 0 -->
<graded_buoyancy>
<default_density>1000</default_density>
<density_change>
<above_depth>0</above_depth>
<density>1</density>
</density_change>
</graded_buoyancy>
<!-- Enable by model name -->
<enable>bluerov2</enable>
</plugin>

<include>
<uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun</uri>
</include>

</world>
</sdf>

0 comments on commit 75b2fa7

Please sign in to comment.