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

fix(launch): update launch files to match new autoware universe package naming #27

Merged
merged 6 commits into from
Sep 6, 2024
Merged
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
9 changes: 9 additions & 0 deletions .cspell.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
{
"version": "0.2",
"language": "en",
"allowCompoundWords": false,
"words": [
"crossvalidation",
"roswrapper"
]
}
27 changes: 15 additions & 12 deletions edge_auto_launch/config/centerpoint.param.yaml
Original file line number Diff line number Diff line change
@@ -1,15 +1,18 @@
/**:
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
cloud_capacity: 2000000
model_params:
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]
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]
27 changes: 15 additions & 12 deletions edge_auto_launch/config/centerpoint_tiny.param.yaml
Original file line number Diff line number Diff line change
@@ -1,15 +1,18 @@
/**:
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
cloud_capacity: 2000000
model_params:
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]
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]
8 changes: 8 additions & 0 deletions edge_auto_launch/config/roi_sync.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,11 @@
input_offset_ms: [50.0, 50.0]
timeout_ms: 70.0
match_threshold_ms: 50.0
image_buffer_size: 15
debug_mode: false
filter_scope_min_x: -100.0
filter_scope_min_y: -100.0
filter_scope_min_z: -100.0
filter_scope_max_x: 100.0
filter_scope_max_y: 100.0
filter_scope_max_z: 100.0
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.30000001192092896
Color: 255; 255; 255
Class: autoware_auto_perception_rviz_plugin/DetectedObjects
Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
Expand Down Expand Up @@ -159,7 +159,7 @@ Visualization Manager:
CYCLIST:
Alpha: 1
Color: 30; 144; 255
Class: autoware_auto_perception_rviz_plugin/DetectedObjects
Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ Visualization Manager:
CYCLIST:
Alpha: 0.30000001192092896
Color: 255; 255; 255
Class: autoware_auto_perception_rviz_plugin/DetectedObjects
Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
Expand Down Expand Up @@ -160,7 +160,7 @@ Visualization Manager:
CYCLIST:
Alpha: 1
Color: 30; 144; 255
Class: autoware_auto_perception_rviz_plugin/DetectedObjects
Class: autoware_perception_rviz_plugin/DetectedObjects
Display Acceleration: true
Display Label: true
Display PoseWithCovariance: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
<group>
<push-ros-namespace namespace="$(var lidar_frame)/$(var camera_frame)"/>
<!-- image_decompressor -->
<node pkg="image_transport_decompressor" exec="image_transport_decompressor_node" name="decompressor" output="screen">
<node pkg="autoware_image_transport_decompressor" exec="image_transport_decompressor_node" name="decompressor" output="screen">
<remap from="decompressor/input/compressed_image" to="$(var compressed_image_topic)"/>
<remap from="decompressor/output/raw_image" to="image_raw"/>
</node>
Expand All @@ -44,7 +44,7 @@
<arg name="pointcloud_topic" value="$(var pointcloud_topic)"/>
<arg name="image_topic" value="image_raw"/>
</include>
<!-- intaractive_calibrator -->
<!-- interactive -->
<node pkg="extrinsic_interactive_calibrator" exec="interactive_calibrator" name="interactive_calibrator" output="screen">
<remap from="pointcloud" to="$(var pointcloud_topic)"/>
<remap from="image" to="$(var compressed_image_topic)"/>
Expand All @@ -65,6 +65,6 @@
<node pkg="tf2_ros" exec="static_transform_publisher" name="estimated_base_link_broadcaster" output="screen" args="--x 0.0 --y 0.0 --z 0.0 --qx 0.0 --qy 0.0 --qz 0.0 --qw 1.0 --frame-id lidar --child-frame-id camera0/camera_link" />
<node pkg="tf2_ros" exec="static_transform_publisher" name="estimated_base_link_broadcaster" output="screen" args="--x 0.0 --y 0.0 --z 0.0 --qx 0.0 --qy 0.0 --qz 0.0 --qw 1.0 --frame-id lidar --child-frame-id camera1/camera_link" />

<!-- visuzalization -->
<!-- visualization -->
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)"/>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<group>
<push-ros-namespace namespace="$(var lidar_frame)/$(var camera_frame)"/>
<!-- image_decompressor -->
<node pkg="image_transport_decompressor" exec="image_transport_decompressor_node" name="decompressor" output="screen">
<node pkg="autoware_image_transport_decompressor" exec="image_transport_decompressor_node" name="decompressor" output="screen">
<remap from="decompressor/input/compressed_image" to="$(var compressed_image_topic)"/>
<remap from="decompressor/output/raw_image" to="image_raw"/>
</node>
Expand All @@ -42,7 +42,7 @@
<arg name="pointcloud_topic" value="$(var pointcloud_topic)"/>
<arg name="image_topic" value="image_raw"/>
</include>
<!-- intaractive_calibrator -->
<!-- interactive_calibrator -->
<node pkg="extrinsic_interactive_calibrator" exec="interactive_calibrator" name="interactive_calibrator" output="screen">
<remap from="pointcloud" to="$(var pointcloud_topic)"/>
<remap from="image" to="$(var compressed_image_topic)"/>
Expand All @@ -63,6 +63,6 @@
<node pkg="tf2_ros" exec="static_transform_publisher" name="estimated_base_link_broadcaster" output="screen" args="--x 0.0 --y 0.0 --z 0.0 --qx 0.0 --qy 0.0 --qz 0.0 --qw 1.0 --frame-id lidar --child-frame-id camera0/camera_link" />
<node pkg="tf2_ros" exec="static_transform_publisher" name="estimated_base_link_broadcaster" output="screen" args="--x 0.0 --y 0.0 --z 0.0 --qx 0.0 --qy 0.0 --qz 0.0 --qw 1.0 --frame-id lidar --child-frame-id camera1/camera_link" />

<!-- visuzalization -->
<!-- visualization -->
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)"/>
</launch>
4 changes: 2 additions & 2 deletions edge_auto_launch/launch/component/crop_box_filter.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

<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">
<node pkg="autoware_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)"/>
Expand All @@ -31,7 +31,7 @@

<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">
<composable_node pkg="autoware_pointcloud_preprocessor" plugin="autoware::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)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<arg name="lidar_model"/>
<arg name="calibration_mode" default="automatic"/>

<include file="$(find-pkg-share extrinsic_tag_based_calibrator)/launch/apriltag_16h5.launch.py">
<include file="$(find-pkg-share tag_based_pnp_calibrator)/launch/apriltag_16h5.launch.py">
<arg name="image_topic" value="$(var image_topic)"/>
<arg name="camera_info_topic" value="$(var camera_info_topic)"/>
</include>
Expand All @@ -16,7 +16,7 @@
<arg name="pointcloud_topic" value="$(var pointcloud_topic)"/>
</include>

<node pkg="extrinsic_tag_based_calibrator" exec="extrinsic_tag_based_calibrator" name="extrinsic_tag_based_calibrator_node" output="screen">
<node pkg="tag_based_pnp_calibrator" exec="tag_based_pnp_calibrator" name="tag_based_pnp_calibrator" output="screen">
<param name="calib_rate" value="10.0"/>
<param name="parent_frame" value="$(var parent_frame)"/>
<param name="child_frame" value="$(var child_frame)"/>
Expand All @@ -29,7 +29,7 @@
<param name="max_tag_distance" value="20.0"/>
<param name="max_allowed_homography_error" value="0.5"/>
<param name="dynamics_model" value="static"/>
<!--constant_velicity,static-->
<!--constant_velocity,static-->
<param name="calibration_crossvalidation_training_ratio" value="0.7"/>
<param name="calibration_convergence_min_pairs" value="9"/>
<param name="calibration_convergence_min_area_percentage" value="0.1"/>
Expand Down
34 changes: 15 additions & 19 deletions edge_auto_launch/launch/component/hesai_at128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,15 @@
<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"/>
<arg name="setup_sensor" default="False"/>

<arg name="ptp_profile" default="1588v2" description="1588v2|802.1as|automotive"/>
<arg name="ptp_domain" default="0" description="PTP Domain [0-127]."/>
<arg name="ptp_transport_type" default="UDP" description="1588v2 supports 'UDP' or 'L2', other profiles only L2 (HW)"/>
<arg name="ptp_switch_type" default="NON_TSN" description="For automotive profile,'TSN' or 'NON_TSN'"/>
<arg name="delay_hw_ms" default="1000" description="hw driver startup delay in milliseconds."/>
<arg name="delay_monitor_ms" default="2000" description="hw monitor startup delay in milliseconds."/>
<arg name="retry_hw" default="True" description="hw driver startup retry (false when using pcap)."/>

<group>
<node_container pkg="rclcpp_components" exec="component_container" name="nebula_at128_node" namespace="/">
Expand Down Expand Up @@ -50,24 +58,12 @@
<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)"/>
<param name="delay_hw_ms" value="$(var delay_hw_ms)"/>
<param name="retry_hw" value="$(var retry_hw)"/>
<param name="ptp_profile" value="$(var ptp_profile)"/>
<param name="ptp_domain" value="$(var ptp_domain)"/>
<param name="ptp_transport_type" value="$(var ptp_transport_type)"/>
<param name="ptp_switch_type" value="$(var ptp_switch_type)"/>
<extra_arg name="use_intra_process_comms" value="true"/>
</composable_node>
</load_composable_node>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,28 @@
# Copyright 2024 The Autoware Contributors
#
# 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.


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):
"""Return Launch Configuration for the TF between the lidar and the camera."""
tf_file = LaunchConfiguration('tf_file_path').perform(context)
with open(tf_file, 'r') as f:
tf_data = json.load(f)
Expand Down Expand Up @@ -44,11 +61,11 @@ def launch_setup(context, *args, **kwargs):
])
]


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

14 changes: 8 additions & 6 deletions edge_auto_launch/launch/component/lidar_centerpoint.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,24 +2,26 @@
<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="$(find-pkg-share lidar_centerpoint)/data"/>
<arg name="model_path" default="$(env HOME)/autoware_data/lidar_centerpoint"/>
<arg name="model_param_path" default="$(find-pkg-share edge_auto_launch)/config/$(var model_name).param.yaml"/>
<arg name="class_remapper_param_path" default="$(find-pkg-share edge_auto_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="has_variance" 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">
<node pkg="autoware_lidar_centerpoint" exec="autoware_lidar_centerpoint_node" name="autoware_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="post_process_params.score_threshold" value="$(var score_threshold)"/>
<param name="model_params.has_twist" value="$(var has_twist)"/>
<param name="model_params.has_variance" value="$(var has_twist)"/>
<param name="densification_params.world_frame_id" value="$(var densification_world_frame_id)"/>
<param name="densification_params.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"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<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">
<node pkg="autoware_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)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<group>
<push-ros-namespace namespace="ground_segmentation"/>
<node_container pkg="rclcpp_components" exec="component_container" name="container" namespace="">
<composable_node pkg="ground_segmentation" plugin="ground_segmentation::ScanGroundFilterComponent" name="ground_segmentation" namespace="">
<composable_node pkg="autoware_ground_segmentation" plugin="autoware::ground_segmentation::ScanGroundFilterComponent" name="ground_segmentation" namespace="">
<remap from="input" to="$(var input/pointcloud)"/>
<remap from="output" to="$(var output/pointcloud)"/>
<param from="$(var param_path)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="voxel_size_z" default="0.1"/>

<group>
<node pkg="pointcloud_preprocessor" exec="voxel_grid_downsample_filter_node" name="voxel_downsample_filter">
<node pkg="autoware_pointcloud_preprocessor" exec="voxel_grid_downsample_filter_node" name="voxel_downsample_filter">
<remap from="input" to="$(var input/pointcloud)"/>
<remap from="output" to="$(var output/pointcloud)"/>
<param name="voxel_size_x" value="$(var voxel_size_x)"/>
Expand Down
2 changes: 1 addition & 1 deletion edge_auto_launch/launch/perception_at128_sample.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="sensor_height" default="1.0"/>

<!-- vehicle_info -->
<include file="$(find-pkg-share vehicle_info_util)/launch/vehicle_info.launch.py">
<include file="$(find-pkg-share autoware_vehicle_info_utils)/launch/vehicle_info.launch.py">
<arg name="vehicle_info_param_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/vehicle_info.param.yaml"/>
</include>

Expand Down
2 changes: 1 addition & 1 deletion edge_auto_launch/launch/perception_xt32_sample.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
<arg name="input/pointcloud" value="/perception/obstacle_segmentation/pointcloud"/>
<arg name="output/objects" value="clusters"/>
</include>
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
<include file="$(find-pkg-share autoware_shape_estimation)/launch/shape_estimation.launch.xml">
<arg name="input/objects" value="clusters"/>
<arg name="output/objects" value="objects_with_feature"/>
<arg name="node_name" value="shape_estimation"/>
Expand Down
Loading
Loading