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: add at128 perception example #11

Open
wants to merge 6 commits into
base: anvil-dev
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
70 changes: 70 additions & 0 deletions edge_auto_jetson_launch/config/can_assign_matrix.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
/**:
ros__parameters:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN <-roi_msg
[
1,
0,
0,
0,
0,
0,
0,
0, # UNKNOWN <-detected_objects
0,
1,
0,
0,
0,
0,
0,
0, # CAR
0,
0,
1,
0,
0,
0,
0,
0, # TRUCK
0,
0,
0,
1,
0,
0,
0,
0, # BUS
0,
0,
0,
0,
1,
0,
0,
0, # TRAILER
0,
0,
0,
0,
0,
1,
0,
0, # MOTORBIKE
0,
0,
0,
0,
0,
0,
1,
0, # BICYCLE
0,
0,
0,
0,
0,
0,
0,
1,
] # PEDESTRIAN
15 changes: 15 additions & 0 deletions edge_auto_jetson_launch/config/centerpoint.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
point_feature_size: 4
max_voxel_size: 40000
point_cloud_range: [-89.6, -89.6, -3.0, 89.6, 89.6, 5.0]
voxel_size: [0.32, 0.32, 8.0]
downsample_factor: 1
encoder_in_feature_size: 9
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
15 changes: 15 additions & 0 deletions edge_auto_jetson_launch/config/centerpoint_tiny.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
point_feature_size: 4
max_voxel_size: 40000
point_cloud_range: [-76.8, -76.8, -2.0, 76.8, 76.8, 4.0]
voxel_size: [0.32, 0.32, 6.0]
downsample_factor: 2
encoder_in_feature_size: 9
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
38 changes: 38 additions & 0 deletions edge_auto_jetson_launch/config/detection_class_remapper.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/**:
ros__parameters:
allow_remapping_by_area_matrix:
# NOTE(kl): We turn all vehicles into trailers if they go over 3x12 [m^2].
# NOTE(kl): We turn cars into trucks if they have an area between 2.2 x 5.5 and 3.0 * 12.0 [m^2]
# row: original class. column: class to remap to
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 0, 1, 0, 1, 0, 0, 0, #CAR
0, 0, 0, 0, 1, 0, 0, 0, #TRUCK
0, 0, 0, 0, 1, 0, 0, 0, #BUS
0, 0, 0, 0, 0, 0, 0, 0, #TRAILER
0, 0, 0, 0, 0, 0, 0, 0, #MOTORBIKE
0, 0, 0, 0, 0, 0, 0, 0, #BICYCLE
0, 0, 0, 0, 0, 0, 0, 0] #PEDESTRIAN

min_area_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN
0.000, 0.000, 12.100, 0.000, 36.000, 0.000, 0.000, 0.000, #CAR
0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #TRUCK
0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #BUS
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN


max_area_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN
0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN
5 changes: 5 additions & 0 deletions edge_auto_jetson_launch/config/roi_sync.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
input_offset_ms: [50.0, 50.0]
timeout_ms: 70.0
match_threshold_ms: 50.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
<launch>
<arg name="input/pointcloud" default="input/pointcloud"/>
<arg name="output/pointcloud" default="output/pointcloud"/>
<arg name="frame_id" default="lidar"/>

<arg name="min_x" default="-100.0"/>
<arg name="min_y" default="-100.0"/>
<arg name="min_z" default="-100.0"/>
<arg name="max_x" default="100.0"/>
<arg name="max_y" default="100.0"/>
<arg name="max_z" default="100.0"/>
<arg name="negative" default="false" description="If true, points outside of the box will be published"/>
<arg name="container_name" default=""/>

<let name="empty_container_is_specified" value="$(eval 'not &quot;$(var container_name)&quot;')" />
<group if="$(var empty_container_is_specified)">
<node pkg="pointcloud_preprocessor" exec="crop_box_filter_node" name="crop_box_filter">
<remap from="input" to="$(var input/pointcloud)"/>
<remap from="output" to="$(var output/pointcloud)"/>
<param name="input_frame" value="$(var frame_id)"/>
<param name="output_frame" value="$(var frame_id)"/>
<param name="min_x" value="$(var min_x)"/>
<param name="min_y" value="$(var min_y)"/>
<param name="min_z" value="$(var min_z)"/>
<param name="max_x" value="$(var max_x)"/>
<param name="max_y" value="$(var max_y)"/>
<param name="max_z" value="$(var max_z)"/>
<param name="negative" value="$(var negative)"/>
</node>
</group>

<group unless="$(var empty_container_is_specified)">
<load_composable_node target="$(var container_name)">
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::CropBoxFilterComponent" name="crop_box_filter">
<param name="input_frame" value="$(var frame_id)"/>
<param name="output_frame" value="$(var frame_id)"/>
<param name="min_x" value="$(var min_x)"/>
<param name="min_y" value="$(var min_y)"/>
<param name="min_z" value="$(var min_z)"/>
<param name="max_x" value="$(var max_x)"/>
<param name="max_y" value="$(var max_y)"/>
<param name="max_z" value="$(var max_z)"/>
<param name="negative" value="$(var negative)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</load_composable_node>
</group>

</launch>
75 changes: 75 additions & 0 deletions edge_auto_jetson_launch/launch/component/hesai_at128.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
<launch>
<arg name="live_sensor" default="True"/>
<arg name="sensor_model" default="PandarAT128"/>
<arg name="return_mode" default="Strongest"/>
<arg name="frame_id" default="lidar"/>
<arg name="scan_phase" default="0.0"/>
<arg name="namespace" default=""/>
<arg name="calibration_file" default="$(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).csv"/>
<arg name="correction_file" default="$(find-pkg-share nebula_decoders)/calibration/hesai/$(var sensor_model).dat"/>
<arg name="sensor_ip" default="192.168.1.201"/>
<arg name="host_ip" default="192.168.1.100"/>
<arg name="data_port" default="2368"/>
<arg name="gnss_port" default="10110"/>
<arg name="packet_mtu_size" default="1500"/>
<arg name="rotation_speed" default="200"/>
<arg name="cloud_min_angle" default="0"/>
<arg name="cloud_max_angle" default="360" />
<arg name="dual_return_distance_threshold" default="0.1"/>
<arg name="diag_span" default="1000"/>
<arg name="setup_sensor" default="True"/>

<group>
<node_container pkg="rclcpp_components" exec="component_container" name="nebula_at128_node" namespace="/">
<composable_node pkg="nebula_ros" plugin="HesaiDriverRosWrapper" name="hesai_driver_roswrapper_node" namespace="$(var namespace)">

Check warning on line 24 in edge_auto_jetson_launch/launch/component/hesai_at128.launch.xml

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (roswrapper)
<param name="sensor_model" value="$(var sensor_model)"/>
<param name="return_mode" value="$(var return_mode)"/>
<param name="frame_id" value="$(var frame_id)"/>
<param name="scan_phase" value="$(var scan_phase)"/>
<param name="calibration_file" value="$(var calibration_file)"/>
<param name="correction_file" value="$(var correction_file)"/>
<remap from="pandar_points" to="pointcloud_raw"/>
<extra_arg name="use_intra_process_comms" value="true"/>
</composable_node>
</node_container>

<load_composable_node target="nebula_at128_node" if="$(var live_sensor)">
<composable_node pkg="nebula_ros" plugin="HesaiHwInterfaceRosWrapper" name="hesai_hw_interface_ros_wrapper_node" namespace="$(var namespace)">
<param name="sensor_model" value="$(var sensor_model)"/>
<param name="return_mode" value="$(var return_mode)"/>
<param name="frame_id" value="$(var frame_id)"/>
<param name="scan_phase" value="$(var scan_phase)"/>
<param name="sensor_ip" value="$(var sensor_ip)"/>
<param name="frame_id" value="$(var frame_id)"/>
<param name="host_ip" value="$(var host_ip)"/>
<param name="data_port" value="$(var data_port)"/>
<param name="gnss_port" value="$(var gnss_port)"/>
<param name="packet_mtu_size" value="$(var packet_mtu_size)"/>
<param name="rotation_speed" value="$(var rotation_speed)"/>
<param name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<param name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<param name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<param name="setup_sensor" value="$(var setup_sensor)"/>
<extra_arg name="use_intra_process_comms" value="true"/>
</composable_node>
<composable_node pkg="nebula_ros" plugin="HesaiHwMonitorRosWrapper" name="hesai_hw_monitor_ros_wrapper_node" namespace="$(var namespace)">
<param name="sensor_model" value="$(var sensor_model)"/>
<param name="return_mode" value="$(var return_mode)"/>
<param name="frame_id" value="$(var frame_id)"/>
<param name="scan_phase" value="$(var scan_phase)"/>
<param name="sensor_ip" value="$(var sensor_ip)"/>
<param name="frame_id" value="$(var frame_id)"/>
<param name="host_ip" value="$(var host_ip)"/>
<param name="data_port" value="$(var data_port)"/>
<param name="gnss_port" value="$(var gnss_port)"/>
<param name="packet_mtu_size" value="$(var packet_mtu_size)"/>
<param name="rotation_speed" value="$(var rotation_speed)"/>
<param name="cloud_min_angle" value="$(var cloud_min_angle)"/>
<param name="cloud_max_angle" value="$(var cloud_max_angle)"/>
<param name="diag_span" value="$(var diag_span)"/>
<param name="dual_return_distance_threshold" value="$(var dual_return_distance_threshold)"/>
<extra_arg name="use_intra_process_comms" value="true"/>
</composable_node>
</load_composable_node>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
import json

def launch_setup(context, *args, **kwargs):
tf_file = LaunchConfiguration('tf_file_path').perform(context)
with open(tf_file, 'r') as f:
tf_data = json.load(f)

return [
Node(
name="lidar_camera_tf_publisher",
package='tf2_ros',
executable='static_transform_publisher',
arguments=[
'--x', str(tf_data['transform']['translation']['x']),
'--y', str(tf_data['transform']['translation']['y']),
'--z', str(tf_data['transform']['translation']['z']),
'--qx', str(tf_data['transform']['rotation']['x']),
'--qy', str(tf_data['transform']['rotation']['y']),
'--qz', str(tf_data['transform']['rotation']['z']),
'--qw', str(tf_data['transform']['rotation']['w']),
'--frame-id', str(tf_data['header']['frame_id']),
'--child-frame-id', str(tf_data['child_frame_id'])
]),
Node(
name="camera_optical_link_publisher",
package='tf2_ros',
executable='static_transform_publisher',
arguments=[
'--x', '0.0',
'--y', '0.0',
'--z', '0.0',
'--qx', '0.5',
'--qy', '-0.5',
'--qz', '0.5',
'--qw', '-0.5',
'--frame-id', str(tf_data['child_frame_id']),
'--child-frame-id', str(tf_data['child_frame_id'].replace('camera_link',
'camera_optical_link'))
])
]

def generate_launch_description():
return LaunchDescription(
[
DeclareLaunchArgument("tf_file_path"),
OpaqueFunction(function=launch_setup),
]
)

Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<launch>
<arg name="input/pointcloud" default="input/pointcloud"/>
<arg name="output/objects" default="output/objects"/>
<arg name="model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
<arg name="model_path" default="/opt/autoware/data/lidar_centerpoint/"/>
<arg name="model_param_path" default="$(find-pkg-share edge_auto_jetson_launch)/config/$(var model_name).param.yaml"/>
<arg name="class_remapper_param_path" default="$(find-pkg-share edge_auto_jetson_launch)/config/detection_class_remapper.param.yaml"/>
<arg name="score_threshold" default="0.35"/>
<arg name="densification_world_frame_id" default="map"/>
<arg name="densification_num_past_frames" default="1"/>
<arg name="has_twist" default="false"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>

<group>
<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param name="score_threshold" value="$(var score_threshold)"/>
<param name="densification_world_frame_id" value="$(var densification_world_frame_id)"/>
<param name="densification_num_past_frames" value="$(var densification_num_past_frames)"/>
<param name="trt_precision" value="fp16"/>
<param name="has_twist" value="$(var has_twist)"/>
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
<param name="build_only" value="$(var build_only)"/>
<param from="$(var model_param_path)"/>
<param from="$(var class_remapper_param_path)"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
<launch>
<arg name="input/rois_number" default="2"/>
<arg name="input/rois0" default="input/rois0"/>
<arg name="input/camera_info0" default="input/camera_info0"/>
<arg name="input/rois1" default="input/rois1"/>
<arg name="input/camera_info1" default="input/camera_info1"/>

<arg name="input/objects" default="input/objects"/>
<arg name="output/objects" default="output/objects"/>
<arg name="sync_param_path" default="$(find-pkg-share edge_auto_jetson_launch)/config/roi_sync.param.yaml"/>
<arg name="can_assign_matrix_param_path" default="$(find-pkg-share edge_auto_jetson_launch)/config/can_assign_matrix.yaml"/>

<!-- for eval variable-->
<arg name="input_rois_number" default="$(var input/rois_number)"/>

<group>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '1' &quot;)" from="input/rois0" to="$(var input/rois0)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '1' &quot;)" from="input/camera_info0" to="$(var input/camera_info0)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '2' &quot;)" from="input/rois1" to="$(var input/rois1)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '2' &quot;)" from="input/camera_info1" to="$(var input/camera_info1)"/>

<node pkg="image_projection_based_fusion" exec="roi_detected_object_fusion_node" name="roi_detected_object_fusion" output="screen">
<param name="rois_number" value="$(var input/rois_number)"/>
<param from="$(var sync_param_path)"/>
<remap from="input" to="$(var input/objects)"/>
<remap from="output" to="$(var output/objects)"/>
<param name="passthrough_lower_bound_probability_thresholds" value="[0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35]"/>
<param name="use_roi_probability" value="false"/>
<param name="roi_probability_threshold" value="0.5"/>
<param name="min_iou_threshold" value="0.3"/>
<param name="debug_mode" value="false"/>
<param name="trust_distances" value="[100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0]"/>
<param from="$(var can_assign_matrix_param_path)"/>
</node>
</group>
</launch>
Loading
Loading