-
Notifications
You must be signed in to change notification settings - Fork 165
/
description.launch.py
97 lines (84 loc) · 3.16 KB
/
description.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
97
# Copyright (c) 2021 Juan Miguel Jimeno
#
# 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 launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, Command, PathJoinSubstitution, EnvironmentVariable
from launch.conditions import IfCondition
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
robot_base = os.getenv('LINOROBOT2_BASE')
urdf_path = PathJoinSubstitution(
[FindPackageShare("linorobot2_description"), "urdf/robots", f"{robot_base}.urdf.xacro"]
)
rviz_config_path = PathJoinSubstitution(
[FindPackageShare('linorobot2_description'), 'rviz', 'description.rviz']
)
return LaunchDescription([
DeclareLaunchArgument(
name='urdf',
default_value=urdf_path,
description='URDF path'
),
DeclareLaunchArgument(
name='publish_joints',
default_value='true',
description='Launch joint_states_publisher'
),
DeclareLaunchArgument(
name='rviz',
default_value='false',
description='Run rviz'
),
DeclareLaunchArgument(
name='use_sim_time',
default_value='false',
description='Use simulation time'
),
Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
condition=IfCondition(LaunchConfiguration("publish_joints")),
parameters=[
{'use_sim_time': LaunchConfiguration('use_sim_time')}
]
),
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[
{
'use_sim_time': LaunchConfiguration('use_sim_time'),
'robot_description': Command(['xacro ', LaunchConfiguration('urdf')])
}
]
),
Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', rviz_config_path],
condition=IfCondition(LaunchConfiguration("rviz")),
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}]
)
])
#sources:
#https://navigation.ros.org/setup_guides/index.html#
#https://answers.ros.org/question/374976/ros2-launch-gazebolaunchpy-from-my-own-launch-file/
#https://github.com/ros2/rclcpp/issues/940