17from ament_index_python.packages
import get_package_share_directory
19from launch
import LaunchDescription
20from launch.actions
import DeclareLaunchArgument, ExecuteProcess
21from launch.conditions
import IfCondition, UnlessCondition
22from launch.substitutions
import LaunchConfiguration, PythonExpression
23from launch_ros.actions.node
import Node
27 declare_use_simulator_cmd = DeclareLaunchArgument(
28 "use_simulator", default_value=
"False", description=
"Whether to execute gzclient)"
31 use_simulator = LaunchConfiguration(
"use_simulator")
32 world = LaunchConfiguration(
"world")
33 headless = LaunchConfiguration(
"headless")
34 show_gz_lidar = LaunchConfiguration(
"show_gz_lidar")
36 sm_dance_bot_warehouse_dir = get_package_share_directory(
"sm_dance_bot_warehouse")
37 launch_dir = os.path.join(sm_dance_bot_warehouse_dir,
"launch")
39 declare_use_simulator_cmd = DeclareLaunchArgument(
40 "use_simulator", default_value=
"True", description=
"Whether to start the simulator"
43 declare_simulator_cmd = DeclareLaunchArgument(
44 "headless", default_value=
"False", description=
"Whether to execute gzclient)"
47 declare_show_gz_lidar = DeclareLaunchArgument(
50 description=
"Whether to apply a namespace to the navigation stack",
53 declare_world_cmd = DeclareLaunchArgument(
55 default_value=os.path.join(sm_dance_bot_warehouse_dir,
"worlds",
"industrial_sim.world"),
56 description=
"Full path to world model file to load",
57 condition=IfCondition(show_gz_lidar),
61 declare_world_cmd_2 = DeclareLaunchArgument(
63 default_value=os.path.join(sm_dance_bot_warehouse_dir,
"worlds",
"industrial_sim.world"),
64 description=
"Full path to world model file to load",
65 condition=UnlessCondition(show_gz_lidar),
68 declare_urdf = DeclareLaunchArgument(
70 default_value=os.path.join(
71 sm_dance_bot_warehouse_dir,
"models",
"turtlebot3_waffle",
"model.sdf"
77 ld = LaunchDescription()
80 "xterm -xrm 'XTerm*scrollBar: true' -xrm 'xterm*rightScrollBar: true' "
81 "-hold -geometry 1000x600 -sl 10000 -e"
84 gzenv = dict(os.environ)
85 model_database_uri = os.environ[
"GAZEBO_MODEL_PATH"]
86 gzenv[
"GAZEBO_MODEL_DATABASE_URI"] = model_database_uri
89 start_gazebo_server_cmd = ExecuteProcess(
90 condition=IfCondition(use_simulator),
94 "libgazebo_ros_init.so",
96 "libgazebo_ros_factory.so",
106 start_gazebo_client_cmd = ExecuteProcess(
107 condition=IfCondition(PythonExpression([use_simulator,
" and not ", headless])),
114 spawn_entity_node = Node(
115 package=
"gazebo_ros",
116 executable=
"spawn_entity.py",
122 LaunchConfiguration(
"urdf"),
135 ld.add_action(declare_simulator_cmd)
136 ld.add_action(declare_use_simulator_cmd)
137 ld.add_action(declare_world_cmd)
138 ld.add_action(declare_world_cmd_2)
139 ld.add_action(declare_urdf)
141 ld.add_action(declare_show_gz_lidar)
143 ld.add_action(start_gazebo_server_cmd)
144 ld.add_action(start_gazebo_client_cmd)
145 ld.add_action(spawn_entity_node)
def generate_launch_description()