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

chore(traffic_light_fine_detector_and_classifier): rework parameters #6216

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
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,9 @@
<let name="all_camera_namespaces" value="[$(var namespace1)]" if="$(eval &quot; '$(var image_number)' == '1' &quot;)"/>
<let name="all_camera_namespaces" value="[$(var namespace1), $(var namespace2)]" if="$(eval &quot; '$(var image_number)' >= '2' &quot;)"/>

<arg name="fine_detector_label_path" default="$(var traffic_light_fine_detector_model_path)/$(var traffic_light_fine_detector_label_name)"/>
<arg name="fine_detector_model_path" default="$(var traffic_light_fine_detector_model_path)/$(var traffic_light_fine_detector_model_name).onnx"/>
<arg name="car_classifier_label_path" default="$(var traffic_light_classifier_model_path)/$(var car_traffic_light_classifier_label_name)"/>
<arg name="pedestrian_classifier_label_path" default="$(var traffic_light_classifier_model_path)/$(var pedestrian_traffic_light_classifier_label_name)"/>
<arg name="car_classifier_model_path" default="$(var traffic_light_classifier_model_path)/$(var car_traffic_light_classifier_model_name).onnx"/>
<arg name="pedestrian_classifier_model_path" default="$(var traffic_light_classifier_model_path)/$(var pedestrian_traffic_light_classifier_model_name).onnx"/>
<arg name="fine_detector_param_path" default="$(find-pkg-share traffic_light_fine_detector)/config/traffic_light_fine_detector.param.yaml"/>
<arg name="car_classifier_param_path" default="$(find-pkg-share traffic_light_classifier)/config/car_traffic_light_classifier.param.yaml"/>
<arg name="pedestrian_classifier_param_path" default="$(find-pkg-share traffic_light_classifier)/config/pedestrian_traffic_light_classifier.param.yaml"/>

<!-- namespace1 camera TLR pipeline -->
<group>
Expand Down Expand Up @@ -62,12 +59,9 @@
<arg name="enable_fine_detection" value="$(var enable_fine_detection)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="fine_detector_label_path" value="$(var fine_detector_label_path)"/>
<arg name="fine_detector_model_path" value="$(var fine_detector_model_path)"/>
<arg name="car_classifier_label_path" value="$(var car_classifier_label_path)"/>
<arg name="pedestrian_classifier_label_path" value="$(var pedestrian_classifier_label_path)"/>
<arg name="car_classifier_model_path" value="$(var car_classifier_model_path)"/>
<arg name="pedestrian_classifier_model_path" value="$(var pedestrian_classifier_model_path)"/>
<arg name="fine_detector_param_path" value="$(var fine_detector_param_path)"/>
<arg name="car_classifier_param_path" value="$(var car_classifier_param_path)"/>
<arg name="pedestrian_classifier_param_path" value="$(var pedestrian_classifier_param_path)"/>
<arg name="output/rois" value="$(var output/rois1)"/>
<arg name="output/traffic_signals" value="$(var output/traffic_signals1)"/>
<arg name="output/car/traffic_signals" value="$(var output/car/traffic_signals1)"/>
Expand Down Expand Up @@ -119,12 +113,9 @@
<arg name="enable_fine_detection" value="$(var enable_fine_detection)"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="fine_detector_label_path" value="$(var fine_detector_label_path)"/>
<arg name="fine_detector_model_path" value="$(var fine_detector_model_path)"/>
<arg name="car_classifier_label_path" value="$(var car_classifier_label_path)"/>
<arg name="pedestrian_classifier_label_path" value="$(var pedestrian_classifier_label_path)"/>
<arg name="car_classifier_model_path" value="$(var car_classifier_model_path)"/>
<arg name="pedestrian_classifier_model_path" value="$(var pedestrian_classifier_model_path)"/>
<arg name="fine_detector_param_path" value="$(var fine_detector_param_path)"/>
<arg name="car_classifier_param_path" value="$(var car_classifier_param_path)"/>
<arg name="pedestrian_classifier_param_path" value="$(var pedestrian_classifier_param_path)"/>
<arg name="output/rois" value="$(var output/rois2)"/>
<arg name="output/traffic_signals" value="$(var output/traffic_signals2)"/>
<arg name="output/car/traffic_signals" value="$(var output/car/traffic_signals2)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,234 +17,200 @@
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.parameter_descriptions import ParameterFile


def generate_launch_description():
launch_arguments = []

def add_launch_arg(name: str, default_value=None, description=None):
# a default_value of None is equivalent to not passing that kwarg at all
launch_arguments.append(
DeclareLaunchArgument(name, default_value=default_value, description=description)
)

fine_detector_share_dir = get_package_share_directory("traffic_light_fine_detector")
classifier_share_dir = get_package_share_directory("traffic_light_classifier")
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",
)
add_launch_arg(
"output/car/traffic_signals", "/perception/traffic_light_recognition/car/traffic_signals"
)
add_launch_arg(
"output/pedestrian/traffic_signals",
"/perception/traffic_light_recognition/pedestrian/traffic_signals",
)

# traffic_light_fine_detector
add_launch_arg(
"fine_detector_model_path",
os.path.join(fine_detector_share_dir, "data", "tlr_yolox_s.onnx"),
)
add_launch_arg(
"fine_detector_label_path",
os.path.join(fine_detector_share_dir, "data", "tlr_labels.txt"),
)
add_launch_arg("fine_detector_precision", "fp16")
add_launch_arg("fine_detector_score_thresh", "0.3")
add_launch_arg("fine_detector_nms_thresh", "0.65")

add_launch_arg("approximate_sync", "False")

# traffic_light_classifier
add_launch_arg("classifier_type", "1")
add_launch_arg(
"car_classifier_model_path",
os.path.join(classifier_share_dir, "data", "traffic_light_classifier_efficientNet_b1.onnx"),
)
add_launch_arg(
"pedestrian_classifier_model_path",
os.path.join(
classifier_share_dir, "data", "pedestrian_traffic_light_classifier_efficientNet_b1.onnx"
),
)
add_launch_arg(
"car_classifier_label_path", os.path.join(classifier_share_dir, "data", "lamp_labels.txt")
)
add_launch_arg(
"pedestrian_classifier_label_path",
os.path.join(classifier_share_dir, "data", "lamp_labels_ped.txt"),
)
add_launch_arg("classifier_precision", "fp16")
add_launch_arg("classifier_mean", "[123.675, 116.28, 103.53]")
add_launch_arg("classifier_std", "[58.395, 57.12, 57.375]")
add_launch_arg("backlight_threshold", "0.85")

add_launch_arg("use_intra_process", "False")
add_launch_arg("use_multithread", "False")

def launch_setup(context, *args, **kwargs):
def create_parameter_dict(*args):
result = {}
for x in args:
result[x] = LaunchConfiguration(x)
return result

fine_detector_model_param = ParameterFile(
param_file=LaunchConfiguration("fine_detector_param_path").perform(context),
allow_substs=True,
)
car_traffic_light_classifier_model_param = ParameterFile(
param_file=LaunchConfiguration("car_classifier_param_path").perform(context),
allow_substs=True,
)
pedestrian_traffic_light_classifier_model_param = ParameterFile(
param_file=LaunchConfiguration("pedestrian_classifier_param_path").perform(context),
allow_substs=True,
)

container = ComposableNodeContainer(
name="traffic_light_node_container",
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[
ComposableNode(
package="traffic_light_classifier",
plugin="traffic_light::TrafficLightClassifierNodelet",
name="car_traffic_light_classifier",
namespace="classification",
parameters=[
{
"approximate_sync": LaunchConfiguration("approximate_sync"),
"classifier_type": LaunchConfiguration("classifier_type"),
"classify_traffic_light_type": 0,
"classifier_model_path": LaunchConfiguration("car_classifier_model_path"),
"classifier_label_path": LaunchConfiguration("car_classifier_label_path"),
"classifier_precision": LaunchConfiguration("classifier_precision"),
"classifier_mean": LaunchConfiguration("classifier_mean"),
"classifier_std": LaunchConfiguration("classifier_std"),
"backlight_threshold": LaunchConfiguration("backlight_threshold"),
}
],
parameters=[car_traffic_light_classifier_model_param],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", LaunchConfiguration("output/rois")),
("~/output/traffic_signals", "classified/car/traffic_signals"),
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
),
ComposableNode(
package="traffic_light_classifier",
plugin="traffic_light::TrafficLightClassifierNodelet",
name="pedestrian_traffic_light_classifier",
namespace="classification",
parameters=[
{
"approximate_sync": LaunchConfiguration("approximate_sync"),
"classifier_type": LaunchConfiguration("classifier_type"),
"classify_traffic_light_type": 1,
"classifier_model_path": LaunchConfiguration(
"pedestrian_classifier_model_path"
),
"classifier_label_path": LaunchConfiguration(
"pedestrian_classifier_label_path"
),
"classifier_precision": LaunchConfiguration("classifier_precision"),
"classifier_mean": LaunchConfiguration("classifier_mean"),
"classifier_std": LaunchConfiguration("classifier_std"),
"backlight_threshold": LaunchConfiguration("backlight_threshold"),
}
],
parameters=[pedestrian_traffic_light_classifier_model_param],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", LaunchConfiguration("output/rois")),
("~/output/traffic_signals", "classified/pedestrian/traffic_signals"),
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
),
ComposableNode(
package="traffic_light_visualization",
plugin="traffic_light::TrafficLightRoiVisualizerNodelet",
name="traffic_light_roi_visualizer",
parameters=[create_parameter_dict("enable_fine_detection")],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/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"),
("~/output/image/theora", "debug/rois/theora"),
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
),
],
output="both",
)

decompressor_loader = LoadComposableNodes(
composable_node_descriptions=[
ComposableNode(
package="image_transport_decompressor",
plugin="image_preprocessor::ImageTransportDecompressor",
name="traffic_light_image_decompressor",
parameters=[{"encoding": "rgb8"}],
remappings=[
(
"~/input/compressed_image",
[LaunchConfiguration("input/image"), "/compressed"],
),
("~/output/raw_image", LaunchConfiguration("input/image")),
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
),
],
target_container=container,
condition=IfCondition(LaunchConfiguration("enable_image_decompressor")),
)

fine_detector_param = create_parameter_dict(
"fine_detector_model_path",
"fine_detector_label_path",
"fine_detector_precision",
"fine_detector_score_thresh",
"fine_detector_nms_thresh",
)

fine_detector_loader = LoadComposableNodes(
composable_node_descriptions=[
ComposableNode(
package="traffic_light_fine_detector",
plugin="traffic_light::TrafficLightFineDetectorNodelet",
name="traffic_light_fine_detector",
namespace="detection",
parameters=[fine_detector_param],
parameters=[fine_detector_model_param],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", "rough/rois"),
("~/expect/rois", "expect/rois"),
("~/output/rois", LaunchConfiguration("output/rois")),
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
),
],
target_container=container,
condition=IfCondition(LaunchConfiguration("enable_fine_detection")),
)

return [container, decompressor_loader, fine_detector_loader]

Check notice on line 159 in launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Large Method

launch_setup has 124 lines, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.


def generate_launch_description():
launch_arguments = []

def add_launch_arg(name: str, default_value=None, description=None):
# a default_value of None is equivalent to not passing that kwarg at all
launch_arguments.append(
DeclareLaunchArgument(name, default_value=default_value, description=description)
)

fine_detector_share_dir = get_package_share_directory("traffic_light_fine_detector")
classifier_share_dir = get_package_share_directory("traffic_light_classifier")
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",
)
add_launch_arg(
"output/car/traffic_signals", "/perception/traffic_light_recognition/car/traffic_signals"
)
add_launch_arg(
"output/pedestrian/traffic_signals",
"/perception/traffic_light_recognition/pedestrian/traffic_signals",
)

# traffic_light_fine_detector
add_launch_arg(
"fine_detector_param_path",
os.path.join(fine_detector_share_dir, "config", "traffic_light_fine_detector.param.yaml"),
)

# traffic_light_classifier
add_launch_arg(
"car_classifier_param_path",
os.path.join(
classifier_share_dir, "config", "car_traffic_light_classifier_efficientNet.param.yaml"
),
)
add_launch_arg(
"pedestrian_classifier_param_path",
os.path.join(
classifier_share_dir,
"config",
"pedestrian_traffic_light_classifier_efficientNet.param.yaml",
),
)

add_launch_arg("use_intra_process", "False")
add_launch_arg("use_multithread", "False")

set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
Expand All @@ -262,8 +228,6 @@
*launch_arguments,
set_container_executable,
set_container_mt_executable,
container,
decompressor_loader,
fine_detector_loader,
OpaqueFunction(function=launch_setup),

Check notice on line 231 in launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Large Method

generate_launch_description is no longer above the threshold for lines of code. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
]
)
2 changes: 2 additions & 0 deletions perception/traffic_light_classifier/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,7 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)

ament_auto_package(INSTALL_TO_SHARE
launch
config
)

else()
Expand All @@ -147,6 +148,7 @@ else()

ament_auto_package(INSTALL_TO_SHARE
launch
config
)

endif()
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
/**:
ros__parameters:
approximate_sync: false
classifier_label_path: "$(var traffic_light_classifier_model_path)/$(var car_traffic_light_classifier_label_name)"
classifier_model_path: "$(var traffic_light_classifier_model_path)/$(var car_traffic_light_classifier_model_name).onnx"
classifier_precision: fp16
classifier_mean: [123.675, 116.28, 103.53]
classifier_std: [58.395, 57.12, 57.375]
backlight_threshold: 0.85
classifier_type: 1 #classifier_type {hsv_filter: 0, cnn: 1}
classify_traffic_light_type: 0 #classify_traffic_light_type {car: 0, pedestrian:1}
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
/**:
ros__parameters:
approximate_sync: false
classifier_label_path: "$(var traffic_light_classifier_model_path)/$(var pedestrian_traffic_light_classifier_label_name)"
classifier_model_path: "$(var traffic_light_classifier_model_path)/$(var pedestrian_traffic_light_classifier_model_name).onnx"
classifier_precision: fp16
classifier_mean: [123.675, 116.28, 103.53]
classifier_std: [58.395, 57.12, 57.375]
backlight_threshold: 0.85
classifier_type: 1 #classifier_type {hsv_filter: 0, cnn: 1}
classify_traffic_light_type: 1 #classify_traffic_light_type {car: 0, pedestrian:1}
Original file line number Diff line number Diff line change
Expand Up @@ -2,32 +2,14 @@
<arg name="input/image" default="~/image_raw"/>
<arg name="input/rois" default="~/rois"/>
<arg name="output/traffic_signals" default="classified/traffic_signals"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="classifier_label_path" default="$(var data_path)/traffic_light_classifier/lamp_labels.txt" description="classifier label path"/>
<arg name="classifier_model_path" default="$(var data_path)/traffic_light_classifier/traffic_light_classifier_mobilenetv2_batch_6.onnx" description="classifier onnx model path"/>
<arg name="classifier_precision" default="fp16"/>

<arg name="use_gpu" default="true"/>
<!-- classifier_type {hsv_filter: 0, cnn: 1} -->
<arg name="classifier_type" default="1" if="$(var use_gpu)"/>
<arg name="classifier_type" default="0" unless="$(var use_gpu)"/>
<!-- classify_traffic_light_type {car: 0, pedestrian:1} -->
<arg name="classify_traffic_light_type" default="0"/>

<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
miursh marked this conversation as resolved.
Show resolved Hide resolved
<arg name="backlight_threshold" default="0.85" description="overwrite signals if the RoI image intensity is greater than this value"/>
<arg name="traffic_light_classifier_param_path" default="$(find-pkg-share traffic_light_classifier)/config/traffic_light_classifier.param.yaml" description="classifier param path"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>

<node pkg="traffic_light_classifier" exec="traffic_light_classifier_node" name="traffic_light_classifier" output="screen">
<remap from="~/input/image" to="$(var input/image)"/>
<remap from="~/input/rois" to="$(var input/rois)"/>
<remap from="~/output/traffic_signals" to="$(var output/traffic_signals)"/>
<param name="approximate_sync" value="false"/>
<param name="classifier_type" value="$(var classifier_type)"/>
<param name="classify_traffic_light_type" value="$(var classify_traffic_light_type)"/>
<param name="classifier_label_path" value="$(var classifier_label_path)"/>
<param name="classifier_model_path" value="$(var classifier_model_path)"/>
<param name="classifier_precision" value="$(var classifier_precision)"/>
<param from="$(var traffic_light_classifier_param_path)" allow_substs="true"/>
<param name="build_only" value="$(var build_only)"/>
<param name="backlight_threshold" value="$(var backlight_threshold)"/>
</node>
</launch>
2 changes: 2 additions & 0 deletions perception/traffic_light_fine_detector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -101,12 +101,14 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)

ament_auto_package(INSTALL_TO_SHARE
launch
config
)

else()
message(STATUS "TrafficLightFineDetector won't be built, CUDA and/or TensorRT were not found.")
# to avoid launch file missing without a gpu
ament_auto_package(INSTALL_TO_SHARE
launch
config
)
endif()
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
fine_detector_label_path: "$(var traffic_light_fine_detector_model_path)/$(var traffic_light_fine_detector_label_name)"
fine_detector_model_path: "$(var traffic_light_fine_detector_model_path)/$(var traffic_light_fine_detector_model_name).onnx"
fine_detector_precision: fp16
fine_detector_score_thresh: 0.3
fine_detector_nms_thresh: 0.65
Loading
Loading