Skip to content

Commit

Permalink
added launch and config file for using point_cloud_fusion_node + poin…
Browse files Browse the repository at this point in the history
…t_type_adapter (#21)

# PR Details
## Description
This PR adds a new launch and config file for launching the
[point_type_adapter](https://github.com/usdot-fhwa-stol/autoware.auto/tree/develop/AutowareAuto/src/tools/point_type_adapter)
and
[point_cloud_fusion_node](https://github.com/usdot-fhwa-stol/autoware.auto/tree/develop/AutowareAuto/src/perception/filters/point_cloud_fusion_nodes),
Autoware.Auto's ROS2 version of the
[points_concat_filter](https://github.com/usdot-fhwa-stol/autoware.ai/tree/carma-develop/core_perception/points_preprocessor/nodes/points_concat_filter)
package in Autoware.AI. This is configured to fuse the point clouds from
the two LiDAR sensors onboard the CARMA freight trucks.

Related PRs:
- [usdotfhwastol/carma-config
#330](usdot-fhwa-stol/carma-config#330)
- [usdotfhwastol/carma-velodyne-lidar-driver
#111](usdot-fhwa-stol/carma-velodyne-lidar-driver#111)

## Related Jira Key
[CAR-5961](https://usdot-carma.atlassian.net/browse/CAR-5961)

## Motivation and Context
Currently, freightliner trucks equipped with CARMA Platform have two
velodyne lidars (compared to the single velodyne lidar on our passenger
vehicles equipped with CARMA Platform), and the autoware.ai
‘[points_concat_filter](https://github.com/usdot-fhwa-stol/autoware.ai/tree/carma-develop/core_perception/points_preprocessor/nodes/points_concat_filter)’
node (a ROS 1 Noetic node) is used to concatenate these two point clouds
into a single point cloud to be used by the rest of the system. As part
of the overall migration from ROS 1 Noetic to ROS 2 Foxy for CARMA
Platform, the system should leverage the ROS 2 Foxy version of this node
made available in Autoware.Auto.

## How Has This Been Tested?

This was tested by launching CARMA Platform on the freight truck and
verifying that `point_cloud_fusion_nodes` fused the scans from the two
velodyne sensors and published the result with the correct topic name
and frame id.

## Types of changes


- [ ] Defect fix (non-breaking change that fixes an issue)
- [x] New feature (non-breaking change that adds functionality)
- [ ] Breaking change (fix or feature that cause existing functionality
to change)

## Checklist:

- [ ] I have added any new packages to the sonar-scanner.properties file
- [ ] My change requires a change to the documentation.
- [ ] I have updated the documentation accordingly.
- [x] I have read the
[**CONTRIBUTING**](https://github.com/usdot-fhwa-stol/carma-platform/blob/develop/Contributing.md)
document.
- [ ] I have added tests to cover my changes.
- [ ] All new and existing tests passed.


[CAR-5961]:
https://usdot-carma.atlassian.net/browse/CAR-5961?atlOrigin=eyJpIjoiNWRkNTljNzYxNjVmNDY3MDlhMDU5Y2ZhYzA5YTRkZjUiLCJwIjoiZ2l0aHViLWNvbS1KU1cifQ
  • Loading branch information
john-chrosniak authored Apr 17, 2024
2 parents 907a87e + be2b701 commit f740821
Show file tree
Hide file tree
Showing 5 changed files with 93 additions and 2 deletions.
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
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

0 comments on commit f740821

Please sign in to comment.