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
26 declare_use_simulator_cmd = DeclareLaunchArgument(
27 "use_simulator", default_value=
"False", description=
"Whether to execute gzclient)"
30 use_simulator = LaunchConfiguration(
"use_simulator")
31 world = LaunchConfiguration(
"world")
32 headless = LaunchConfiguration(
"headless")
33 show_gz_lidar = LaunchConfiguration(
"show_gz_lidar")
35 sm_dance_bot_strikes_back_dir = get_package_share_directory(
"sm_dance_bot_strikes_back")
36 launch_dir = os.path.join(sm_dance_bot_strikes_back_dir,
"launch")
38 declare_use_simulator_cmd = DeclareLaunchArgument(
39 "use_simulator", default_value=
"True", description=
"Whether to start the simulator"
42 declare_simulator_cmd = DeclareLaunchArgument(
43 "headless", default_value=
"False", description=
"Whether to execute gzclient)"
46 declare_show_gz_lidar = DeclareLaunchArgument(
49 description=
"Whether to apply a namespace to the navigation stack",
52 declare_world_cmd = DeclareLaunchArgument(
54 default_value=os.path.join(
55 sm_dance_bot_strikes_back_dir,
"worlds",
"ridgeback_race.world"
57 description=
"Full path to world model file to load",
58 condition=IfCondition(show_gz_lidar),
61 declare_world_cmd_2 = DeclareLaunchArgument(
63 default_value=os.path.join(
64 sm_dance_bot_strikes_back_dir,
"worlds",
"ridgeback_race_no_lidar.world"
66 description=
"Full path to world model file to load",
67 condition=UnlessCondition(show_gz_lidar),
71 ld = LaunchDescription()
76 gzenv = dict(os.environ)
77 model_database_uri = os.environ[
"GAZEBO_MODEL_PATH"]
78 gzenv[
"GAZEBO_MODEL_DATABASE_URI"] = model_database_uri
81 start_gazebo_server_cmd = ExecuteProcess(
82 condition=IfCondition(use_simulator),
83 cmd=[
"gzserver",
"-s",
"libgazebo_ros_init.so", world,
"--verbose"],
89 start_gazebo_client_cmd = ExecuteProcess(
90 condition=IfCondition(PythonExpression([use_simulator,
" and not ", headless])),
98 ld.add_action(declare_simulator_cmd)
99 ld.add_action(declare_use_simulator_cmd)
100 ld.add_action(declare_world_cmd)
101 ld.add_action(declare_world_cmd_2)
103 ld.add_action(declare_show_gz_lidar)
105 ld.add_action(start_gazebo_server_cmd)
106 ld.add_action(start_gazebo_client_cmd)
def generate_launch_description()