Skip to content

Commit 02ad5b2

Browse files
committed
added ability to launch python or cpp turtle example
1 parent 0866290 commit 02ad5b2

File tree

1 file changed

+29
-3
lines changed

1 file changed

+29
-3
lines changed

elevation_mapping_cupy/launch/elevation_mapping_turtle.launch.py

Lines changed: 29 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,8 @@
33
from launch_ros.actions import Node
44
from ament_index_python.packages import get_package_share_directory
55
from launch.actions import DeclareLaunchArgument
6-
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
6+
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, PythonExpression
7+
from launch.conditions import IfCondition, UnlessCondition
78
from launch_ros.descriptions import ParameterFile
89

910

@@ -37,6 +38,13 @@ def generate_launch_description():
3738
)
3839
rviz_config = LaunchConfiguration('rviz_config')
3940

41+
use_python_node_arg = DeclareLaunchArgument(
42+
'use_python_node',
43+
default_value='false',
44+
description='Use the Python node if true'
45+
)
46+
use_python_node = LaunchConfiguration('use_python_node')
47+
4048
# RViz Node
4149
rviz_node = Node(
4250
package='rviz2',
@@ -46,6 +54,20 @@ def generate_launch_description():
4654
parameters=[{'use_sim_time': use_sim_time}],
4755
output='screen'
4856
)
57+
elevation_mapping_node_py = Node(
58+
package='elevation_mapping_cupy',
59+
executable='elevation_mapping_node.py',
60+
name='elevation_mapping_node',
61+
output='screen',
62+
parameters=[
63+
ParameterFile(core_param_path, allow_substs=True),
64+
turtle_param_path,
65+
{'use_sim_time': use_sim_time}
66+
],
67+
condition=IfCondition(use_python_node)
68+
# condition=IfCondition(PythonExpression(use_python_node))
69+
)
70+
4971
elevation_mapping_node = Node(
5072
package='elevation_mapping_cupy',
5173
executable='elevation_mapping_node',
@@ -55,12 +77,16 @@ def generate_launch_description():
5577
ParameterFile(core_param_path, allow_substs=True),
5678
turtle_param_path,
5779
{'use_sim_time': use_sim_time}
58-
]
59-
)
80+
],
81+
condition=UnlessCondition(use_python_node)
82+
# condition=UnlessCondition(PythonExpression(use_python_node))
83+
)
6084

6185
return LaunchDescription([
6286
use_sim_time_arg,
6387
rviz_config_arg,
88+
use_python_node_arg,
89+
elevation_mapping_node_py,
6490
elevation_mapping_node,
6591
rviz_node
6692
])

0 commit comments

Comments
 (0)