forked from ROBOTIS-GIT/turtlebot3_simulations
-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathspawn_turtlebot3.launch.py
96 lines (81 loc) · 2.97 KB
/
spawn_turtlebot3.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# 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.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
# Get the urdf file
TURTLEBOT3_MODEL = os.environ['TURTLEBOT3_MODEL']
model_folder = 'turtlebot3_' + TURTLEBOT3_MODEL
urdf_path = os.path.join(
get_package_share_directory('turtlebot3_gazebo'),
'models',
model_folder,
'model.sdf'
)
# Launch configuration variables specific to simulation
x_pose = LaunchConfiguration('x_pose', default='0.0')
y_pose = LaunchConfiguration('y_pose', default='0.0')
# Declare the launch arguments
declare_x_position_cmd = DeclareLaunchArgument(
'x_pose', default_value='0.0',
description='Specify namespace of the robot')
declare_y_position_cmd = DeclareLaunchArgument(
'y_pose', default_value='0.0',
description='Specify namespace of the robot')
start_gazebo_ros_spawner_cmd = Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-name', TURTLEBOT3_MODEL,
'-file', urdf_path,
'-x', x_pose,
'-y', y_pose,
'-z', '0.01'
],
output='screen',
)
bridge_params = os.path.join(
get_package_share_directory('turtlebot3_gazebo'),
'params',
'turtlebot3_waffle_bridge.yaml'
)
start_gazebo_ros_bridge_cmd = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'--ros-args',
'-p',
f'config_file:={bridge_params}',
],
output='screen',
)
start_gazebo_ros_image_bridge_cmd = Node(
package='ros_gz_image',
executable='image_bridge',
arguments=['/camera/image_raw'],
output='screen',
)
ld = LaunchDescription()
# Declare the launch options
ld.add_action(declare_x_position_cmd)
ld.add_action(declare_y_position_cmd)
# Add any conditioned actions
ld.add_action(start_gazebo_ros_spawner_cmd)
ld.add_action(start_gazebo_ros_bridge_cmd)
ld.add_action(start_gazebo_ros_image_bridge_cmd)
return ld