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(tier4_perception_launch): update traffic light launch #4176

Merged
Original file line number Diff line number Diff line change
Expand Up @@ -3,30 +3,38 @@
<arg name="enable_image_decompressor" default="true" description="enable image decompressor"/>
<arg name="enable_fine_detection" default="true" description="enable fine position adjustment of traffic light"/>
<arg name="fine_detector_label_path" default="$(find-pkg-share traffic_light_fine_detector)/data/tlr_labels.txt" description="fine detector label path"/>
<arg name="fine_detector_model_path" default="$(find-pkg-share traffic_light_fine_detector)/data/tlr_yolox_s.onnx" description="fine detector onnx model path"/>
<arg name="input/cloud" default="/sensing/lidar/top/pointcloud_raw" description="point cloud for occlusion prediction"/>
<arg name="fine_detector_model_path" default="$(find-pkg-share traffic_light_fine_detector)/data/tlr_yolox_s_batch_6.onnx" description="fine detector onnx model path"/>
<arg name="classifier_label_path" default="$(find-pkg-share traffic_light_classifier)/data/lamp_labels.txt" description="classifier label path"/>
<arg name="classifier_model_path" default="$(find-pkg-share traffic_light_classifier)/data/traffic_light_classifier_efficientNet_b1.onnx" description="classifier onnx model path"/>
<arg name="classifier_model_path" default="$(find-pkg-share traffic_light_classifier)/data/traffic_light_classifier_mobilenetv2_batch_6.onnx" description="classifier onnx model path"/>
<arg name="output/traffic_signals" default="/perception/traffic_light_recognition/traffic_signals"/>
<arg name="use_crosswalk_traffic_light_estimator" default="true" description="output pedestrian's traffic light signals"/>
<arg name="use_crosswalk_traffic_light_estimator" default="false" description="output pedestrian's traffic light signals"/>
miursh marked this conversation as resolved.
Show resolved Hide resolved
<let name="namespace1" value="camera6"/>
<let name="namespace2" value="camera7"/>
<let name="output/rois1" value="/perception/traffic_light_recognition/$(var namespace1)/rois"/>
<let name="output/rois2" value="/perception/traffic_light_recognition/$(var namespace2)/rois"/>
miursh marked this conversation as resolved.
Show resolved Hide resolved
<let name="output/traffic_signals1" value="/perception/traffic_light_recognition/$(var namespace1)/traffic_signals"/>
<let name="output/traffic_signals2" value="/perception/traffic_light_recognition/$(var namespace2)/traffic_signals"/>
<let name="all_camera_namespaces" value="[$(var namespace1), $(var namespace2)]"/>
<!-- camera 6 TLR pipeline -->
<group>
<push-ros-namespace namespace="$(var namespace1)"/>
<let name="input/image" value="/sensing/camera/$(var namespace1)/image_raw"/>
<let name="input/camera_info" value="/sensing/camera/$(var namespace1)/camera_info"/>
<let name="map_based_detector_output_topic" value="rough/rois" if="$(var enable_fine_detection)"/>
<let name="map_based_detector_output_topic" value="rois" unless="$(var enable_fine_detection)"/>
<let name="map_based_detector_output_topic" value="$(var output/rois1)" unless="$(var enable_fine_detection)"/>

<node pkg="topic_tools" exec="relay" name="traffic_light_camra_info_relay" args="$(var input/camera_info) camera_info"/>
<include file="$(find-pkg-share traffic_light_map_based_detector)/launch/traffic_light_map_based_detector.launch.xml">
<arg name="input/camera_info" value="$(var input/camera_info)"/>
<arg name="min_timestamp_offset" value="-0.3"/>
<arg name="expect/rois" value="expect/rois"/>
<arg name="output/rois" value="$(var map_based_detector_output_topic)"/>
<arg name="output/camera_info" value="camera_info"/>
</include>
<group>
<push-ros-namespace namespace="detection"/>
<include file="$(find-pkg-share traffic_light_map_based_detector)/launch/traffic_light_map_based_detector.launch.xml">
<arg name="input/camera_info" value="$(var input/camera_info)"/>
<arg name="min_timestamp_offset" value="-0.3"/>
<arg name="expect/rois" value="expect/rois"/>
<arg name="output/rois" value="$(var map_based_detector_output_topic)"/>
<arg name="output/camera_info" value="camera_info"/>
</include>
</group>

<include file="$(find-pkg-share tier4_perception_launch)/launch/traffic_light_recognition/traffic_light_node_container.launch.py">
<arg name="input/image" value="$(var input/image)"/>
Expand All @@ -39,7 +47,20 @@
<arg name="fine_detector_model_path" value="$(var fine_detector_model_path)"/>
<arg name="classifier_label_path" value="$(var classifier_label_path)"/>
<arg name="classifier_model_path" value="$(var classifier_model_path)"/>
<arg name="output/rois" value="$(var output/rois1)"/>
<arg name="output/traffic_signals" value="$(var output/traffic_signals1)"/>
</include>

<group>
<push-ros-namespace namespace="classification"/>
<include file="$(find-pkg-share traffic_light_occlusion_predictor)/launch/traffic_light_occlusion_predictor.launch.xml">
<arg name="input/camera_info" value="$(var input/camera_info)"/>
<arg name="input/cloud" value="$(var input/cloud)"/>
<arg name="input/rois" value="$(var output/rois1)"/>
<arg name="input/traffic_signals" value="estimated/traffic_signals"/>
<arg name="output/traffic_signals" value="$(var output/traffic_signals1)"/>
</include>
</group>
</group>
<!-- camera 7 TLR pipeline -->
<group>
Expand All @@ -50,13 +71,16 @@
<let name="map_based_detector_output_topic" value="rois" unless="$(var enable_fine_detection)"/>

<node pkg="topic_tools" exec="relay" name="traffic_light_camra_info_relay" args="$(var input/camera_info) camera_info"/>
<include file="$(find-pkg-share traffic_light_map_based_detector)/launch/traffic_light_map_based_detector.launch.xml">
<arg name="input/camera_info" value="$(var input/camera_info)"/>
<arg name="min_timestamp_offset" value="-0.04"/>
<arg name="expect/rois" value="expect/rois"/>
<arg name="output/rois" value="$(var map_based_detector_output_topic)"/>
<arg name="output/camera_info" value="camera_info"/>
</include>
<group>
<push-ros-namespace namespace="detection"/>
<include file="$(find-pkg-share traffic_light_map_based_detector)/launch/traffic_light_map_based_detector.launch.xml">
<arg name="input/camera_info" value="$(var input/camera_info)"/>
<arg name="min_timestamp_offset" value="-0.04"/>
<arg name="expect/rois" value="expect/rois"/>
<arg name="output/rois" value="$(var map_based_detector_output_topic)"/>
<arg name="output/camera_info" value="camera_info"/>
</include>
</group>

<include file="$(find-pkg-share tier4_perception_launch)/launch/traffic_light_recognition/traffic_light_node_container.launch.py">
<arg name="input/image" value="$(var input/image)"/>
Expand All @@ -69,7 +93,20 @@
<arg name="fine_detector_model_path" value="$(var fine_detector_model_path)"/>
<arg name="classifier_label_path" value="$(var classifier_label_path)"/>
<arg name="classifier_model_path" value="$(var classifier_model_path)"/>
<arg name="output/rois" value="$(var output/rois2)"/>
<arg name="output/traffic_signals" value="$(var output/traffic_signals2)"/>
</include>

<group>
<push-ros-namespace namespace="classification"/>
<include file="$(find-pkg-share traffic_light_occlusion_predictor)/launch/traffic_light_occlusion_predictor.launch.xml">
<arg name="input/camera_info" value="$(var input/camera_info)"/>
<arg name="input/cloud" value="$(var input/cloud)"/>
<arg name="input/rois" value="$(var output/rois2)"/>
<arg name="input/traffic_signals" value="estimated/traffic_signals"/>
<arg name="output/traffic_signals" value="$(var output/traffic_signals2)"/>
</include>
</group>
</group>
<!-- traffic_light_multi_camera_fusion -->
<group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("enable_image_decompressor", "True")
add_launch_arg("enable_fine_detection", "True")
add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw")
add_launch_arg("output/rois", "/perception/traffic_light_recognition/rois")
add_launch_arg(
"output/traffic_signals", "/perception/traffic_light_recognition/traffic_signals"
)

# traffic_light_fine_detector
add_launch_arg(
Expand Down Expand Up @@ -89,6 +93,7 @@ def create_parameter_dict(*args):
package="traffic_light_classifier",
plugin="traffic_light::TrafficLightClassifierNodelet",
name="traffic_light_classifier",
namespace="classification",
parameters=[
create_parameter_dict(
"approximate_sync",
Expand All @@ -102,7 +107,7 @@ def create_parameter_dict(*args):
],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", "rois"),
("~/input/rois", LaunchConfiguration("output/rois")),
("~/output/traffic_signals", "classified/traffic_signals"),
],
extra_arguments=[
Expand All @@ -116,9 +121,9 @@ def create_parameter_dict(*args):
parameters=[create_parameter_dict("enable_fine_detection")],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", "rois"),
("~/input/rough/rois", "rough/rois"),
("~/input/traffic_signals", "traffic_signals"),
("~/input/rois", LaunchConfiguration("output/rois")),
("~/input/rough/rois", "detection/rough/rois"),
("~/input/traffic_signals", LaunchConfiguration("output/traffic_signals")),
("~/output/image", "debug/rois"),
("~/output/image/compressed", "debug/rois/compressed"),
("~/output/image/compressedDepth", "debug/rois/compressedDepth"),
Expand All @@ -138,11 +143,12 @@ def create_parameter_dict(*args):
package="crosswalk_traffic_light_estimator",
plugin="traffic_light::CrosswalkTrafficLightEstimatorNode",
name="crosswalk_traffic_light_estimator",
namespace="classification",
remappings=[
("~/input/vector_map", "/map/vector_map"),
("~/input/route", "/planning/mission_planning/route"),
("~/input/classified/traffic_signals", "classified/traffic_signals"),
("~/output/traffic_signals", "traffic_signals"),
("~/output/traffic_signals", "estimated/traffic_signals"),
],
extra_arguments=[{"use_intra_process_comms": False}],
),
Expand All @@ -157,10 +163,10 @@ def create_parameter_dict(*args):
package="topic_tools",
plugin="topic_tools::RelayNode",
name="classified_signals_relay",
namespace="",
namespace="classification",
parameters=[
{"input_topic": "classified/traffic_signals"},
{"output_topic": "traffic_signals"},
{"output_topic": "estimated/traffic_signals"},
{"type": "autoware_auto_perception_msgs/msg/TrafficSignalArray"},
miursh marked this conversation as resolved.
Show resolved Hide resolved
],
extra_arguments=[
Expand Down Expand Up @@ -209,12 +215,13 @@ def create_parameter_dict(*args):
package="traffic_light_fine_detector",
plugin="traffic_light::TrafficLightFineDetectorNodelet",
name="traffic_light_fine_detector",
namespace="detection",
parameters=[fine_detector_param],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", "rough/rois"),
("~/expect/rois", "expect/rois"),
("~/output/rois", "rois"),
("~/output/rois", LaunchConfiguration("output/rois")),
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
Expand Down