Skip to content

Commit

Permalink
Update robot launch files (#502)
Browse files Browse the repository at this point in the history
  • Loading branch information
ygoumaz authored Nov 1, 2022
1 parent 6ebfccd commit c0040a9
Show file tree
Hide file tree
Showing 5 changed files with 204 additions and 79 deletions.
59 changes: 41 additions & 18 deletions webots_ros2_epuck/launch/robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,19 +29,11 @@
from webots_ros2_driver.utils import controller_url_prefix


def generate_launch_description():
def get_ros2_nodes(*args):
package_dir = get_package_share_directory('webots_ros2_epuck')
world = LaunchConfiguration('world')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', 'epuck_webots.urdf')).read_text()
ros2_control_params = os.path.join(package_dir, 'resource', 'ros2_control.yml')
use_sim_time = LaunchConfiguration('use_sim_time', default=True)

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world])
)

ros2_supervisor = Ros2SupervisorLauncher()

controller_manager_timeout = ['--controller-manager-timeout', '50']
controller_manager_prefix = 'python.exe' if os.name == 'nt' else ''

Expand Down Expand Up @@ -112,6 +104,35 @@ def generate_launch_description():
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_footprint'],
)

return [
joint_state_broadcaster_spawner,
diffdrive_controller_spawner,
robot_state_publisher,
epuck_driver,
footprint_publisher,
epuck_process,
]


def generate_launch_description():
package_dir = get_package_share_directory('webots_ros2_epuck')
world = LaunchConfiguration('world')

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world])
)

ros2_supervisor = Ros2SupervisorLauncher()

# The following line is important!
# This event handler respawns the ROS 2 nodes on simulation reset (supervisor process ends).
reset_handler = launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=ros2_supervisor,
on_exit=get_ros2_nodes,
)
)

return LaunchDescription([
DeclareLaunchArgument(
'world',
Expand All @@ -120,18 +141,20 @@ def generate_launch_description():
),
webots,
ros2_supervisor,
joint_state_broadcaster_spawner,
diffdrive_controller_spawner,
robot_state_publisher,
epuck_driver,
footprint_publisher,
epuck_process,

# This action will kill all nodes once the Webots simulation has exited
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
on_exit=[
launch.actions.UnregisterEventHandler(
event_handler=reset_handler.event_handler
),
launch.actions.EmitEvent(event=launch.events.Shutdown())
],
)
)
])
),

# Add the reset event handler
reset_handler
] + get_ros2_nodes())
49 changes: 37 additions & 12 deletions webots_ros2_mavic/launch/robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,10 @@
from webots_ros2_driver.utils import controller_url_prefix


def generate_launch_description():
def get_ros2_nodes(*args):
package_dir = get_package_share_directory('webots_ros2_mavic')
world = LaunchConfiguration('world')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', 'mavic_webots.urdf')).read_text()

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world])
)

ros2_supervisor = Ros2SupervisorLauncher()

mavic_driver = Node(
package='webots_ros2_driver',
executable='driver',
Expand All @@ -50,6 +43,30 @@ def generate_launch_description():
]
)

return [
mavic_driver,
]


def generate_launch_description():
package_dir = get_package_share_directory('webots_ros2_mavic')
world = LaunchConfiguration('world')

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world])
)

ros2_supervisor = Ros2SupervisorLauncher()

# The following line is important!
# This event handler respawns the ROS 2 nodes on simulation reset (supervisor process ends).
reset_handler = launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=ros2_supervisor,
on_exit=get_ros2_nodes,
)
)

return LaunchDescription([
DeclareLaunchArgument(
'world',
Expand All @@ -58,12 +75,20 @@ def generate_launch_description():
),
webots,
ros2_supervisor,
mavic_driver,

# This action will kill all nodes once the Webots simulation has exited
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
on_exit=[
launch.actions.UnregisterEventHandler(
event_handler=reset_handler.event_handler
),
launch.actions.EmitEvent(event=launch.events.Shutdown())
],
)
)
])
),

# Add the reset event handler
reset_handler
] + get_ros2_nodes())
51 changes: 38 additions & 13 deletions webots_ros2_tesla/launch/robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,10 @@
from webots_ros2_driver.utils import controller_url_prefix


def generate_launch_description():
def get_ros2_nodes(*args):
package_dir = get_package_share_directory('webots_ros2_tesla')
world = LaunchConfiguration('world')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', 'tesla_webots.urdf')).read_text()

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world])
)

ros2_supervisor = Ros2SupervisorLauncher()

tesla_driver = Node(
package='webots_ros2_driver',
executable='driver',
Expand All @@ -55,6 +48,31 @@ def generate_launch_description():
executable='lane_follower',
)

return [
lane_follower,
tesla_driver,
]


def generate_launch_description():
package_dir = get_package_share_directory('webots_ros2_tesla')
world = LaunchConfiguration('world')

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world])
)

ros2_supervisor = Ros2SupervisorLauncher()

# The following line is important!
# This event handler respawns the ROS 2 nodes on simulation reset (supervisor process ends).
reset_handler = launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=ros2_supervisor,
on_exit=get_ros2_nodes,
)
)

return LaunchDescription([
DeclareLaunchArgument(
'world',
Expand All @@ -63,13 +81,20 @@ def generate_launch_description():
),
webots,
ros2_supervisor,
lane_follower,
tesla_driver,

# This action will kill all nodes once the Webots simulation has exited
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
on_exit=[
launch.actions.UnregisterEventHandler(
event_handler=reset_handler.event_handler
),
launch.actions.EmitEvent(event=launch.events.Shutdown())
],
)
)
])
),

# Add the reset event handler
reset_handler
] + get_ros2_nodes())
66 changes: 46 additions & 20 deletions webots_ros2_tiago/launch/robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,9 @@
from webots_ros2_driver.utils import controller_url_prefix


def generate_launch_description():
def get_ros2_nodes(*args):
optional_nodes = []
package_dir = get_package_share_directory('webots_ros2_tiago')
world = LaunchConfiguration('world')
mode = LaunchConfiguration('mode')
use_rviz = LaunchConfiguration('rviz', default=False)
use_nav = LaunchConfiguration('nav', default=False)
use_slam = LaunchConfiguration('slam', default=False)
Expand All @@ -44,13 +42,6 @@ def generate_launch_description():
nav2_map = os.path.join(package_dir, 'resource', 'map.yaml')
use_sim_time = LaunchConfiguration('use_sim_time', default=True)

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world]),
mode=mode
)

ros2_supervisor = Ros2SupervisorLauncher()

controller_manager_timeout = ['--controller-manager-timeout', '50']
controller_manager_prefix = 'python.exe' if os.name == 'nt' else ''

Expand Down Expand Up @@ -135,6 +126,38 @@ def generate_launch_description():
condition=launch.conditions.IfCondition(use_slam)
)

return [
joint_state_broadcaster_spawner,
diffdrive_controller_spawner,
rviz,
robot_state_publisher,
tiago_driver,
footprint_publisher,
slam_toolbox,
] + optional_nodes


def generate_launch_description():
package_dir = get_package_share_directory('webots_ros2_tiago')
world = LaunchConfiguration('world')
mode = LaunchConfiguration('mode')

webots = WebotsLauncher(
world=PathJoinSubstitution([package_dir, 'worlds', world]),
mode=mode
)

ros2_supervisor = Ros2SupervisorLauncher()

# The following line is important!
# This event handler respawns the ROS 2 nodes on simulation reset (supervisor process ends).
reset_handler = launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=ros2_supervisor,
on_exit=get_ros2_nodes,
)
)

return LaunchDescription([
DeclareLaunchArgument(
'world',
Expand All @@ -148,17 +171,20 @@ def generate_launch_description():
),
webots,
ros2_supervisor,
joint_state_broadcaster_spawner,
diffdrive_controller_spawner,
rviz,
robot_state_publisher,
tiago_driver,
footprint_publisher,
slam_toolbox,

# This action will kill all nodes once the Webots simulation has exited
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=webots,
on_exit=[launch.actions.EmitEvent(event=launch.events.Shutdown())],
on_exit=[
launch.actions.UnregisterEventHandler(
event_handler=reset_handler.event_handler
),
launch.actions.EmitEvent(event=launch.events.Shutdown())
],
)
)
] + optional_nodes)
),

# Add the reset event handler
reset_handler
] + get_ros2_nodes())
Loading

0 comments on commit c0040a9

Please sign in to comment.