Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

added launch and config file for using point_cloud_fusion_node + point_type_adapter #21

Merged
merged 20 commits into from
Apr 17, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
bddeb1f
added launch and config file for using point_cloud_fusion_node
john-chrosniak Mar 21, 2024
2e68b17
corrected namespace configuration
JonSmet Mar 27, 2024
5514539
updated pcd field types to include ring index (XYZI -> XYZIF)
JonSmet Mar 27, 2024
71c63d8
added new point type that contains ring index
JonSmet Mar 27, 2024
553f517
updated point type in point_cloud_fusion and point_cloud_fusion_nodes…
JonSmet Mar 28, 2024
82e8770
removed end of scan id
JonSmet Mar 28, 2024
4859264
removed padding from point type struct to align struct size with the …
JonSmet Mar 28, 2024
744674f
increased cloud capacity and fixed topic namespace
JonSmet Mar 29, 2024
335f9aa
changed point cloud type in unit test and restructure package.xml to …
john-chrosniak Apr 1, 2024
fea5383
Merge branch 'car-5961-pcd-fusion-to-ros2' of github.com:usdot-fhwa-s…
john-chrosniak Apr 1, 2024
4aa490c
added docs detailing and justifying the changes made to define the ne…
john-chrosniak Apr 8, 2024
1dde9e1
added copyright docs for changes and new launch file
john-chrosniak Apr 8, 2024
c4ba38e
reverted changes made to use new point type PointXYZIRing in favor of…
john-chrosniak Apr 11, 2024
71d1977
reverted whitespace changes
john-chrosniak Apr 11, 2024
9a5b422
remapped topic names to add point type adapter before fusion node
JonSmet Apr 12, 2024
60e3f67
added namespacing to point_type_adapter_container
JonSmet Apr 12, 2024
d676ad4
added point_type_adapter to launch with point_cloud_fusion in single …
john-chrosniak Apr 15, 2024
27bba96
added necessary extra args
john-chrosniak Apr 15, 2024
00f216b
updated launch file and config to use carma_component_container_mt
john-chrosniak Apr 16, 2024
be2b701
removed rclcpp_components comment
john-chrosniak Apr 16, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<depend>lidar_utils</depend>

<build_depend>autoware_auto_common</build_depend>
<build_depend>carma_cmake_common</build_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand All @@ -21,5 +22,4 @@
<export>
<build_type>ament_cmake</build_type>
</export>
<build_depend>carma_cmake_common</build_depend>
</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
# Copyright (C) 2024 LEIDOS.
#
# 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.

# This file is intended to launch point_cloud_fusion_nodes on CARMA freightliner trucks
# consisting of two Velodyne LiDARs

import launch
JonSmet marked this conversation as resolved.
Show resolved Hide resolved
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable
from carma_ros2_utils.launch.get_current_namespace import GetCurrentNamespace
from carma_ros2_utils.launch.get_log_level import GetLogLevel
from ament_index_python import get_package_share_directory

import os

env_log_levels = EnvironmentVariable('CARMA_ROS_LOGGING_CONFIG', default_value='{ "default_level" : "WARN" }')

point_cloud_fusion_node_pkg_prefix = get_package_share_directory('point_cloud_fusion_nodes')
point_cloud_fusion_node_param_file = os.path.join(point_cloud_fusion_node_pkg_prefix,
'param/point_cloud_fusion.param.yaml')


def generate_launch_description():

point_cloud_fusion_container = ComposableNodeContainer(
package='carma_ros2_utils',
name='point_cloud_fusion_container',
executable='carma_component_container_mt',
namespace=GetCurrentNamespace(),
composable_node_descriptions=[
ComposableNode(
package='point_cloud_fusion_nodes',
plugin='autoware::perception::filters::point_cloud_fusion_nodes::PointCloudFusionNode',
name='point_cloud_fusion_node',
parameters=[point_cloud_fusion_node_param_file],
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('point_cloud_fusion_nodes', env_log_levels) },
],
remappings=[
('output_topic', 'lidar/points_raw'),
('input_topic1', 'velodyne_1/lidar/points_xyzi'),
('input_topic2', 'velodyne_2/lidar/points_xyzi'),

]
),
ComposableNode(
package='point_type_adapter',
plugin='autoware::tools::point_type_adapter::PointTypeAdapterNode',
name='velodyne_1_point_type_adapter_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('point_type_adapter', env_log_levels) },
],
remappings=[('points_raw', 'velodyne_1/lidar/points_raw'),
('points_xyzi', 'velodyne_1/lidar/points_xyzi')]
),
ComposableNode(
package='point_type_adapter',
plugin='autoware::tools::point_type_adapter::PointTypeAdapterNode',
name='velodyne_2_point_type_adapter_node',
extra_arguments=[
{'use_intra_process_comms': True},
{'--log-level' : GetLogLevel('point_type_adapter', env_log_levels) },
],
remappings=[('points_raw', 'velodyne_2/lidar/points_raw'),
('points_xyzi', 'velodyne_2/lidar/points_xyzi')],
)
]
)

return launch.LaunchDescription([point_cloud_fusion_container])
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,12 @@
<depend>tf2_ros</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_sensor_msgs</depend>
<depend>carma_ros2_utils</depend>
<depend>point_type_adapter</depend>

<build_depend>eigen</build_depend>
<build_depend>autoware_auto_common</build_depend>
<build_depend>carma_cmake_common</build_depend>

<build_export_depend>eigen</build_export_depend>

Expand All @@ -36,5 +39,5 @@
<export>
<build_type>ament_cmake</build_type>
</export>
<build_depend>carma_cmake_common</build_depend>

</package>
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
number_of_sources: 2
output_frame_id: "concat_velodyne"
cloud_size: 80000
1 change: 1 addition & 0 deletions AutowareAuto/src/tools/point_type_adapter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<depend>sensor_msgs</depend>
<depend>autoware_auto_common</depend>
<depend>point_cloud_msg_wrapper</depend>
<depend>carma_ros2_utils</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Loading