Skip to content

Commit 8535719

Browse files
committed
turtlebot gazebo용
1 parent 6a98eea commit 8535719

File tree

1 file changed

+127
-0
lines changed

1 file changed

+127
-0
lines changed
Lines changed: 127 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,127 @@
1+
#############################################################################
2+
3+
from launch import LaunchDescription
4+
from launch.substitutions import LaunchConfiguration
5+
6+
import launch_ros.actions
7+
from launch_ros.actions import ComposableNodeContainer
8+
from launch_ros.descriptions import ComposableNode
9+
10+
from ament_index_python.packages import get_package_share_directory
11+
from launch.launch_description_sources import PythonLaunchDescriptionSource
12+
from launch_ros.actions import Node
13+
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
14+
15+
def generate_launch_description():
16+
17+
# Important, required arguments
18+
points_topic1 = LaunchConfiguration('points_topic', default='/tb3_0/velodyne_points')
19+
points_parents_frame_id = LaunchConfiguration('points_parents_frame_id', default='base_link')
20+
imu_topic1 = LaunchConfiguration('imu_topic', default='/tb3_0/imu')
21+
odom_child_frame_id1 = LaunchConfiguration('odom_child_frame_id', default='tb3_0/base_link')
22+
robot_odom_frame_id1 = LaunchConfiguration('robot_odom_frame_id', default='tb3_0/odom')
23+
algined_points_remap1 = LaunchConfiguration('aligned_points', default='/tb3_0/aligned_points')
24+
path_remap1 = LaunchConfiguration('path', default='/tb3_0/path')
25+
26+
points_topic2 = LaunchConfiguration('points_topic', default='/tb3_1/velodyne_points')
27+
imu_topic2 = LaunchConfiguration('imu_topic', default='/tb3_1/imu')
28+
odom_child_frame_id2 = LaunchConfiguration('odom_child_frame_id', default='tb3_1/base_link')
29+
robot_odom_frame_id2 = LaunchConfiguration('robot_odom_frame_id', default='tb3_1/odom')
30+
algined_points_remap2 = LaunchConfiguration('aligned_points', default='/tb3_1/aligned_points')
31+
path_remap2 = LaunchConfiguration('path', default='/tb3_1/path')
32+
33+
# 우선 겹치는 topic들 먼저 처리하기 aligned_points랑 path같은 것들 odom도 마찬가지
34+
35+
globalmap_pcd = DeclareLaunchArgument('globalmap_pcd', default_value='/root/workspace/src/hdl_localization/data/map.pcd', description='Path to the global map PCD file')
36+
37+
# optional arguments
38+
use_imu = LaunchConfiguration('use_imu', default='true')
39+
invert_imu_acc = LaunchConfiguration('invert_imu_acc', default='false')
40+
invert_imu_gyro = LaunchConfiguration('invert_imu_gyro', default='false')
41+
use_global_localization = LaunchConfiguration('use_global_localization', default='false')
42+
enable_robot_odometry_prediction = LaunchConfiguration('enable_robot_odometry_prediction', default='false')
43+
44+
plot_estimation_errors = LaunchConfiguration('plot_estimation_errors', default='false')
45+
46+
container = ComposableNodeContainer(
47+
name='container',
48+
namespace='',
49+
package='rclcpp_components',
50+
executable='component_container',
51+
composable_node_descriptions=[
52+
ComposableNode(
53+
package='hdl_localization',
54+
plugin='hdl_localization::GlobalmapServerNodelet',
55+
name='GlobalmapServerNodelet',
56+
parameters=[
57+
{'globalmap_pcd': LaunchConfiguration('globalmap_pcd')},
58+
{'convert_utm_to_local': True},
59+
{'downsample_resolution': 0.1}]),
60+
ComposableNode(
61+
package='hdl_localization',
62+
plugin='hdl_localization::HdlLocalizationNodelet',
63+
name='HdlLocalizationNode1',
64+
remappings=[('/velodyne_points', points_topic1), ('/gpsimu_driver/imu_data', imu_topic1),
65+
('/aligned_points', algined_points_remap1), ('/path', path_remap1)],
66+
parameters=[
67+
{'points_parents_frame_id': points_parents_frame_id},
68+
{'odom_child_frame_id': odom_child_frame_id1},
69+
{'use_imu': use_imu},
70+
{'invert_acc': invert_imu_acc},
71+
{'invert_gyro': invert_imu_gyro},
72+
{'cool_time_duration': 2.0},
73+
{'enable_robot_odometry_prediction': enable_robot_odometry_prediction},
74+
{'robot_odom_frame_id': robot_odom_frame_id1},
75+
# <!-- available reg_methods: NDT_OMP, NDT_CUDA_P2D, NDT_CUDA_D2D-->
76+
{'reg_method': 'NDT_OMP'},
77+
{'ndt_neighbor_search_method': 'DIRECT7'},
78+
{'ndt_neighbor_search_radius': 1.0},
79+
{'ndt_resolution': 0.5},
80+
{'downsample_resolution': 0.1},
81+
{'specify_init_pose': True},
82+
{'init_pos_x': 0.0},
83+
{'init_pos_y': 0.0},
84+
{'init_pos_z': 0.0},
85+
{'init_ori_w': 1.0},
86+
{'init_ori_x': 0.0},
87+
{'init_ori_y': 0.0},
88+
{'init_ori_z': 0.0},
89+
{'use_global_localization': use_global_localization}]),
90+
ComposableNode(
91+
package='hdl_localization',
92+
plugin='hdl_localization::HdlLocalizationNodelet',
93+
name='HdlLocalizationNode2',
94+
remappings=[('/velodyne_points', points_topic2), ('/gpsimu_driver/imu_data', imu_topic2),
95+
('/aligned_points', algined_points_remap2), ('/path', path_remap2)],
96+
parameters=[
97+
{'points_parents_frame_id': points_parents_frame_id},
98+
{'odom_child_frame_id': odom_child_frame_id2},
99+
{'use_imu': use_imu},
100+
{'invert_acc': invert_imu_acc},
101+
{'invert_gyro': invert_imu_gyro},
102+
{'cool_time_duration': 2.0},
103+
{'enable_robot_odometry_prediction': enable_robot_odometry_prediction},
104+
{'robot_odom_frame_id': robot_odom_frame_id2},
105+
# <!-- available reg_methods: NDT_OMP, NDT_CUDA_P2D, NDT_CUDA_D2D-->
106+
{'reg_method': 'NDT_OMP'},
107+
{'ndt_neighbor_search_method': 'DIRECT7'},
108+
{'ndt_neighbor_search_radius': 1.0},
109+
{'ndt_resolution': 0.5},
110+
{'downsample_resolution': 0.1},
111+
{'specify_init_pose': True},
112+
{'init_pos_x': 0.0},
113+
{'init_pos_y': 0.0},
114+
{'init_pos_z': 0.0},
115+
{'init_ori_w': 1.0},
116+
{'init_ori_x': 0.0},
117+
{'init_ori_y': 0.0},
118+
{'init_ori_z': 0.0},
119+
{'use_global_localization': use_global_localization}])
120+
121+
],
122+
output='screen',
123+
)
124+
125+
return LaunchDescription([globalmap_pcd,
126+
launch_ros.actions.SetParameter(name='use_sim_time', value=True),
127+
container])

0 commit comments

Comments
 (0)