-
Notifications
You must be signed in to change notification settings - Fork 39
/
Copy pathpendulum_bringup.launch.py
129 lines (117 loc) · 4.44 KB
/
pendulum_bringup.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
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
# Copyright 2019 Carlos San Vicente
#
# 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.conditions import IfCondition
import launch.substitutions
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from tracetools_launch.action import Trace
def generate_launch_description():
# Get the bringup directory
bringup_dir = FindPackageShare('pendulum_bringup').find('pendulum_bringup')
# Set robot description parameters
urdf_file = os.path.join(bringup_dir, 'urdf', 'pendulum.urdf')
with open(urdf_file, 'r') as infp:
robot_desc = infp.read()
rsp_params = {'robot_description': robot_desc}
# Set parameter file path
param_file_path = os.path.join(bringup_dir, 'params', 'pendulum.param.yaml')
param_file = launch.substitutions.LaunchConfiguration('params', default=[param_file_path])
# Set rviz config path
rviz_cfg_path = os.path.join(bringup_dir, 'rviz/pendulum.rviz')
# Create the launch configuration variables
autostart_param = DeclareLaunchArgument(
name='autostart',
default_value='True',
description='Automatically start lifecycle nodes')
priority_param = DeclareLaunchArgument(
name='priority',
default_value='0',
description='Set process priority')
cpu_affinity_param = DeclareLaunchArgument(
name='cpu-affinity',
default_value='0',
description='Set process CPU affinity')
with_lock_memory_param = DeclareLaunchArgument(
name='lock-memory',
default_value='False',
description='Lock the process memory')
lock_memory_size_param = DeclareLaunchArgument(
name='lock-memory-size',
default_value='0',
description='Set lock memory size in MB')
config_child_threads_param = DeclareLaunchArgument(
name='config-child-threads',
default_value='False',
description='Configure process child threads (typically DDS threads)')
with_rviz_param = DeclareLaunchArgument(
'rviz',
default_value='False',
description='Launch RVIZ2 in addition to other nodes'
)
trace_param = DeclareLaunchArgument(
'trace',
default_value='False',
description='Launch ROS tracing action'
)
# Node definitions
pendulum_demo_runner = Node(
package='pendulum_demo',
executable='pendulum_demo',
output='screen',
parameters=[param_file],
arguments=[
'--autostart', LaunchConfiguration('autostart'),
'--priority', LaunchConfiguration('priority'),
'--cpu-affinity', LaunchConfiguration('cpu-affinity'),
'--lock-memory', LaunchConfiguration('lock-memory'),
'--lock-memory-size', LaunchConfiguration('lock-memory-size'),
'--config-child-threads', LaunchConfiguration('config-child-threads')
]
)
robot_state_publisher_runner = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[rsp_params],
condition=IfCondition(LaunchConfiguration('rviz'))
)
rviz_runner = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
arguments=['-d', str(rviz_cfg_path)],
condition=IfCondition(LaunchConfiguration('rviz'))
)
ros_tracing = Trace(
session_name='pendulum-tracing-session',
condition=IfCondition(LaunchConfiguration('trace'))
)
return LaunchDescription([
autostart_param,
priority_param,
cpu_affinity_param,
with_lock_memory_param,
lock_memory_size_param,
config_child_threads_param,
with_rviz_param,
robot_state_publisher_runner,
pendulum_demo_runner,
rviz_runner,
trace_param,
ros_tracing
])