sensor_kit.xacro
- Left, right LiDAR 추가로 인한 left, right frame_id 추가
<xacro:VLP-16
parent="sensor_kit_base_link"
name="rslidar_left"
topic="/left/rslidar_points"
hz="10"
samples="220"
gpu="false"
>
<origin
xyz="${calibration['sensor_kit_base_link']['rslidar_left_base_link']['x']}
${calibration['sensor_kit_base_link']['rslidar_left_base_link']['y']}
${calibration['sensor_kit_base_link']['rslidar_left_base_link']['z']}"
rpy="${calibration['sensor_kit_base_link']['rslidar_left_base_link']['roll']}
${calibration['sensor_kit_base_link']['rslidar_left_base_link']['pitch']}
${calibration['sensor_kit_base_link']['rslidar_left_base_link']['yaw']}"
/>
</xacro:VLP-16>
sensor_kit_calibration.yaml
- 각 frame_id와 base_link 간 연결 관계 추가
rslidar_left_base_link:
x: 0.0
y: 0.629
z: 0.42
roll: -1.396267
pitch: 0.0
yaw: 0.0
robosense_lidar_node.launch.py
nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
remappings=[("output", "concat_3lidars/pointcloud")],
parameters=[{
"input_topics": [
"pointcloud_raw_ex","/left/rslidar_points","/right/rslidar_points",
],
"output_frame": LaunchConfiguration("base_frame"),
}],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)