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

feat: acceleration and transport layer #348

Open
wants to merge 12 commits into
base: tier4/universe
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
1 change: 1 addition & 0 deletions aip_xx1_gen2_launch/launch/lidar.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,7 @@ def add_launch_arg(name: str, default_value=None, **kwargs):
)
add_launch_arg("vehicle_mirror_param_file")
add_launch_arg("use_pointcloud_container", "false", description="launch pointcloud container")
add_launch_arg("use_cuda_preprocessor", "true", description="use the cuda layer")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("enable_blockage_diag", "false")
add_launch_arg("return_mode", "Dual")
Expand Down
15 changes: 15 additions & 0 deletions aip_xx1_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="use_pointcloud_container" default="true"/>
<arg name="use_cuda_preprocessor" default="true"/>
<arg name="enable_blockage_diag" default="true"/>
<arg name="udp_only" default="false"/>

Expand All @@ -25,6 +27,9 @@
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="vertical_bins" value="128"/>
<arg name="horizontal_ring_id" value="64"/>
<arg name="is_channel_order_top2down" value="false"/>
Expand All @@ -48,6 +53,9 @@
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="vertical_bins" value="16"/>
<arg name="horizontal_ring_id" value="0"/>
<arg name="is_channel_order_top2down" value="false"/>
Expand All @@ -71,6 +79,9 @@
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="vertical_bins" value="16"/>
<arg name="horizontal_ring_id" value="0"/>
<arg name="is_channel_order_top2down" value="false"/>
Expand All @@ -94,6 +105,9 @@
<arg name="udp_only" value="$(var udp_only)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="vertical_bins" value="16"/>
<arg name="horizontal_ring_id" value="0"/>
<arg name="is_channel_order_top2down" value="false"/>
Expand Down Expand Up @@ -126,6 +140,7 @@
<arg name="base_frame" value="base_link"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

Expand Down
38 changes: 27 additions & 11 deletions aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,17 +37,32 @@
)

# set concat filter as a component
concat_component = ComposableNode(
package="autoware_pointcloud_preprocessor",
plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
if LaunchConfiguration("use_cuda_preprocessor").perform(context):
concat_component = ComposableNode(
package="autoware_cuda_pointcloud_preprocessor",
plugin="autoware::cuda_pointcloud_preprocessor::CudaPointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
("output/cuda", "concatenated/pointcloud/cuda"),
],
parameters=[concatenate_and_time_sync_node_param],
# NOTE(knzo25): when using the cuda blackboard, this setting can not be made global

Check warning on line 51 in aip_xx1_launch/launch/pointcloud_preprocessor.launch.py

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (knzo)
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
else:
concat_component = ComposableNode(
package="autoware_pointcloud_preprocessor",
plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

# load concat or passthrough filter
concat_loader = LoadComposableNodes(
Expand All @@ -69,6 +84,7 @@

add_launch_arg("use_multithread", "False")
add_launch_arg("use_intra_process", "False")
add_launch_arg("use_cuda_preprocessor", "True")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg(
"concatenate_and_time_sync_node_param_path",
Expand Down
1 change: 1 addition & 0 deletions aip_xx1_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<exec_depend>autoware_cuda_pointcloud_preprocessor</exec_depend>
<exec_depend>autoware_glog_component</exec_depend>
<exec_depend>autoware_gnss_poser</exec_depend>
<exec_depend>autoware_imu_corrector</exec_depend>
Expand Down
6 changes: 6 additions & 0 deletions common_sensor_launch/launch/hesai_OT128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,9 @@
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="hesai_node_container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="use_cuda_preprocessor" default="false"/>
<arg name="udp_only" default="false"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
Expand All @@ -31,6 +34,9 @@
<arg name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="ptp_profile" value="automotive"/>
Expand Down
6 changes: 6 additions & 0 deletions common_sensor_launch/launch/hesai_XT32.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="container_name" default="hesai_node_container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="use_pointcloud_container" default="false"/>
<arg name="use_cuda_preprocessor" default="false"/>
<arg name="udp_only" default="false"/>

<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
Expand All @@ -33,6 +36,9 @@
<arg name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="$(var container_name)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="use_cuda_preprocessor" value="$(var use_cuda_preprocessor)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="ptp_profile" value="automotive"/>
Expand Down
Loading
Loading