Skip to content

Commit

Permalink
Changed ParseMultiRobotPose to be a launch substitution class
Browse files Browse the repository at this point in the history
Signed-off-by: Tanner, Gilbert <[email protected]>
  • Loading branch information
TannerGilbert committed Jan 5, 2025
1 parent ca8c1e7 commit 9b31d75
Show file tree
Hide file tree
Showing 3 changed files with 195 additions and 127 deletions.
259 changes: 132 additions & 127 deletions nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
import tempfile

from ament_index_python.packages import get_package_share_directory
from launch import LaunchContext, LaunchDescription
from launch import LaunchDescription
from launch.actions import (AppendEnvironmentVariable, DeclareLaunchArgument,
ExecuteProcess, GroupAction,
IncludeLaunchDescription, LogInfo, OpaqueFunction,
Expand All @@ -28,57 +28,21 @@
from launch.event_handlers import OnShutdown
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, TextSubstitution
import yaml


def parse_robots_argument(robots_arg: str):
robots_dict = {}
if robots_arg:
robots_list = robots_arg.split(';')
for robot in robots_list:
key, value = robot.split('=')
key = key.strip()
value = yaml.safe_load(value.strip())
value.setdefault('x', 0.0)
value.setdefault('y', 0.0)
value.setdefault('z', 0.0)
value.setdefault('roll', 0.0)
value.setdefault('pitch', 0.0)
value.setdefault('yaw', 0.0)
robots_dict[key] = value
return robots_dict


def launch_setup(context: LaunchContext, *args, **kwargs):
from nav2_common.launch import ParseMultiRobotPose


def generate_robot_actions(context, *args, **kwargs):
bringup_dir = get_package_share_directory('nav2_bringup')
launch_dir = os.path.join(bringup_dir, 'launch')

# Simulation settings. On this example all robots are launched with the same settings
world = LaunchConfiguration('world')
map_yaml_file = LaunchConfiguration('map')
use_rviz = LaunchConfiguration('use_rviz')
params_file = LaunchConfiguration('params_file')
autostart = LaunchConfiguration('autostart')
rviz_config_file = LaunchConfiguration('rviz_config')
map_yaml_file = LaunchConfiguration('map')
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
use_rviz = LaunchConfiguration('use_rviz')
log_settings = LaunchConfiguration('log_settings', default='true')

# Start Gazebo with plugin providing the robot spawning service
world_sdf = tempfile.mktemp(prefix='nav2_', suffix='.sdf')
world_sdf_xacro = ExecuteProcess(
cmd=['xacro', '-o', world_sdf, ['headless:=', 'False'], world])
start_gazebo_cmd = ExecuteProcess(
cmd=['gz', 'sim', '-r', '-s', world_sdf],
output='screen',
)

remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
on_shutdown=[
OpaqueFunction(function=lambda _: os.remove(world_sdf))
]))

robots_string = LaunchConfiguration('robots').perform(context)
robots_list = parse_robots_argument(robots_string)
robots_substitution = ParseMultiRobotPose(LaunchConfiguration('robots'))
robots_list = robots_substitution.perform(context)

# Define commands for launching the navigation instances
bringup_cmd_group = []
Expand Down Expand Up @@ -132,109 +96,150 @@ def launch_setup(context: LaunchContext, *args, **kwargs):
)

bringup_cmd_group.append(group)
bringup_cmd_group.append(
LogInfo(msg=['number_of_robots=', str(len(robots_list))]))
return bringup_cmd_group

launch_actions = []

# Add the actions to start gazebo, robots and simulations
launch_actions.append(world_sdf_xacro)
launch_actions.append(start_gazebo_cmd)
launch_actions.append(remove_temp_sdf_file)
def generate_launch_description():
"""
Bring up the multi-robots with given launch arguments.
launch_actions.append(
LogInfo(msg=['number_of_robots=', str(len(robots_list))]))
Launch arguments consist of robot name(which is namespace) and pose for initialization.
Keep general yaml format for pose information.
ex) robots:='robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}'
ex) robots:='robot3={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707};
robot4={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}'
"""
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')

# Simulation settings
world = LaunchConfiguration('world')

# On this example all robots are launched with the same settings
map_yaml_file = LaunchConfiguration('map')
params_file = LaunchConfiguration('params_file')
autostart = LaunchConfiguration('autostart')
rviz_config_file = LaunchConfiguration('rviz_config')
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
log_settings = LaunchConfiguration('log_settings', default='true')

# Declare the launch arguments
declare_world_cmd = DeclareLaunchArgument(
'world',
default_value=os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro'),
description='Full path to world file to load',
)

declare_robots_cmd = DeclareLaunchArgument(
'robots',
default_value='robot1={x: 0.5, y: 0.5, yaw: 0}; robot2={x: -0.5, y: -0.5, yaw: 1.5707}',
description='Robots and their initialization poses in YAML format',
)

declare_map_yaml_cmd = DeclareLaunchArgument(
'map',
default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'),
description='Full path to map file to load',
)

launch_actions.append(
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(
bringup_dir, 'params', 'nav2_params.yaml'
),
description='Full path to the ROS2 parameters file to use for all launched nodes',
)

declare_autostart_cmd = DeclareLaunchArgument(
'autostart',
default_value='false',
description='Automatically startup the stacks',
)

declare_rviz_config_file_cmd = DeclareLaunchArgument(
'rviz_config',
default_value=os.path.join(
bringup_dir, 'rviz', 'nav2_default_view.rviz'),
description='Full path to the RVIZ config file to use.',
)

declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
'use_robot_state_pub',
default_value='True',
description='Whether to start the robot state publisher',
)

declare_use_rviz_cmd = DeclareLaunchArgument(
'use_rviz', default_value='True', description='Whether to start RVIZ'
)

# Start Gazebo with plugin providing the robot spawning service
world_sdf = tempfile.mktemp(prefix='nav2_', suffix='.sdf')
world_sdf_xacro = ExecuteProcess(
cmd=['xacro', '-o', world_sdf, ['headless:=', 'False'], world])
start_gazebo_cmd = ExecuteProcess(
cmd=['gz', 'sim', '-r', '-s', world_sdf],
output='screen',
)

remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
on_shutdown=[
OpaqueFunction(function=lambda _: os.remove(world_sdf))
]))

set_env_vars_resources = AppendEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models'))
set_env_vars_resources2 = AppendEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH',
str(Path(os.path.join(sim_dir)).parent.resolve()))

# Create the launch description and populate
ld = LaunchDescription()
ld.add_action(set_env_vars_resources)
ld.add_action(set_env_vars_resources2)

# Declare the launch options
ld.add_action(declare_world_cmd)
ld.add_action(declare_robots_cmd)
ld.add_action(declare_map_yaml_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_use_rviz_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_rviz_config_file_cmd)
ld.add_action(declare_use_robot_state_pub_cmd)

# Add the actions to start gazebo, robots and simulations
ld.add_action(world_sdf_xacro)
ld.add_action(start_gazebo_cmd)
ld.add_action(remove_temp_sdf_file)

ld.add_action(
LogInfo(condition=IfCondition(log_settings),
msg=['map yaml: ', map_yaml_file])
)
launch_actions.append(
ld.add_action(
LogInfo(condition=IfCondition(log_settings),
msg=['params yaml: ', params_file])
)
launch_actions.append(
ld.add_action(
LogInfo(
condition=IfCondition(log_settings),
msg=['rviz config file: ', rviz_config_file],
)
)
launch_actions.append(
ld.add_action(
LogInfo(
condition=IfCondition(log_settings),
msg=['using robot state pub: ', use_robot_state_pub],
)
)
launch_actions.append(
ld.add_action(
LogInfo(condition=IfCondition(log_settings),
msg=['autostart: ', autostart])
)
ld.add_action(OpaqueFunction(function=generate_robot_actions))

for cmd in bringup_cmd_group:
launch_actions.append(cmd)

return launch_actions


def generate_launch_description():
"""
Bring up the multi-robots with given launch arguments.
Launch arguments consist of robot name(which is namespace) and pose for initialization.
Keep general yaml format for pose information.
ex) robots:='robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}'
ex) robots:='robot3={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707};
robot4={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}'
"""
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')

return LaunchDescription([
DeclareLaunchArgument(
'world',
default_value=os.path.join(
sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro'),
description='Full path to world file to load',
),
DeclareLaunchArgument(
'robots',
description='Robot namespaces and poses (required)'
),
DeclareLaunchArgument(
'map',
default_value=os.path.join(
bringup_dir, 'maps', 'tb3_sandbox.yaml'),
description='Full path to map file to load',
),
DeclareLaunchArgument(
'params_file',
default_value=os.path.join(
bringup_dir, 'params', 'nav2_params.yaml'
),
description='Full path to the ROS2 parameters file to use for all launched nodes',
),
DeclareLaunchArgument(
'autostart',
default_value='false',
description='Automatically startup the stacks',
),
DeclareLaunchArgument(
'rviz_config',
default_value=os.path.join(
bringup_dir, 'rviz', 'nav2_default_view.rviz'),
description='Full path to the RVIZ config file to use.',
),
DeclareLaunchArgument(
'use_robot_state_pub',
default_value='True',
description='Whether to start the robot state publisher',
),
DeclareLaunchArgument(
'use_rviz', default_value='True', description='Whether to start RVIZ'
),
# Set the path to the simulation resources
AppendEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models')),
AppendEnvironmentVariable('GZ_SIM_RESOURCE_PATH', str(
Path(os.path.join(sim_dir)).parent.resolve())),
OpaqueFunction(function=launch_setup)
])
return ld
1 change: 1 addition & 0 deletions nav2_common/nav2_common/launch/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,4 +20,5 @@
'HasNodeParams',
'RewrittenYaml',
'ReplaceString',
'ParseMultiRobotPose',
]
62 changes: 62 additions & 0 deletions nav2_common/nav2_common/launch/parse_multirobot_pose.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
# Copyright (c) 2023 LG Electronics.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Dict, Text

import yaml
from launch.launch_context import LaunchContext
import launch


class ParseMultiRobotPose(launch.Substitution):
"""
A custom substitution to parse the robots argument for multi-robot poses.
Expects input in the format:
robots:="robot1={x: 1.0, y: 1.0, yaw: 0.0}; robot2={x: 2.0, y: 2.0, yaw: 1.5707}"
"""

def __init__(self, robots_argument: launch.SomeSubstitutionsType) -> None:
super().__init__()
self.__robots_argument = robots_argument

def describe(self) -> Text:
"""Return a description of this substitution as a string."""
return ''

def perform(self, context: LaunchContext) -> Dict:
"""
Resolve and parse the robots argument string into a dictionary.
"""
robots_str = self.__robots_argument.perform(context)
if not robots_str:
return {}

multirobots = {}
for robot_entry in robots_str.split(";"):
key_val = robot_entry.strip().split("=")
if len(key_val) != 2:
continue

robot_name, pose_str = key_val[0].strip(), key_val[1].strip()
robot_pose = yaml.safe_load(pose_str)
# Set default values if not provided
robot_pose.setdefault("x", 0.0)
robot_pose.setdefault("y", 0.0)
robot_pose.setdefault("z", 0.0)
robot_pose.setdefault("roll", 0.0)
robot_pose.setdefault("pitch", 0.0)
robot_pose.setdefault("yaw", 0.0)
multirobots[robot_name] = robot_pose
return multirobots

0 comments on commit 9b31d75

Please sign in to comment.