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

[pull] main from autowarefoundation:main #500

Merged
merged 6 commits into from
Feb 27, 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
8 changes: 8 additions & 0 deletions perception/radar_crossing_objects_noise_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,17 @@ rclcpp_components_register_node(radar_crossing_objects_noise_filter_node_compone

# Tests
if(BUILD_TESTING)
find_package(ament_cmake_ros REQUIRED)
list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

file(GLOB_RECURSE test_files test/**/*.cpp)
ament_add_ros_isolated_gtest(radar_crossing_objects_noise_filter ${test_files})

target_link_libraries(radar_crossing_objects_noise_filter
radar_crossing_objects_noise_filter_node_component
)
endif()

# Package
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ class RadarCrossingObjectsNoiseFilterNode : public rclcpp::Node
// Parameter
NodeParam node_param_{};

public:
// Core
bool isNoise(const DetectedObject & object);
};
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
// Copyright 2024 TierIV
//
// 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.

#include <rclcpp/rclcpp.hpp>

#include <gtest/gtest.h>

int main(int argc, char * argv[])
{
testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
bool result = RUN_ALL_TESTS();
rclcpp::shutdown();
return result;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,175 @@
// Copyright 2024 Tier IV, Inc.
//
// 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.

#include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/math/unit_conversion.hpp"

#include <geometry_msgs/msg/point32.hpp>

#include <gtest/gtest.h>

std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode> get_node(
double angle_threshold, double velocity_threshold)
{
rclcpp::NodeOptions node_options;

node_options.parameter_overrides(
{{"angle_threshold", angle_threshold}, {"velocity_threshold", velocity_threshold}});
auto node =
std::make_shared<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode>(
node_options);
return node;
}

autoware_auto_perception_msgs::msg::DetectedObject get_object(
geometry_msgs::msg::Vector3 velocity, geometry_msgs::msg::Point position,
geometry_msgs::msg::Quaternion orientation)
{
autoware_auto_perception_msgs::msg::DetectedObject object;
object.kinematics.twist_with_covariance.twist.linear = velocity;
object.kinematics.pose_with_covariance.pose.position = position;
object.kinematics.pose_with_covariance.pose.orientation = orientation;
return object;
}

TEST(RadarCrossingObjectsFilter, IsNoise)
{
rclcpp::init(0, nullptr);
{
auto velocity = tier4_autoware_utils::createVector3(40.0, 30.0, 0.0);
auto position = tier4_autoware_utils::createPoint(1.0, 0.0, 0.0);
auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0);
auto object = get_object(velocity, position, orientation);
{
double velocity_threshold = 40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_TRUE(node->isNoise(object));
}
{
double velocity_threshold = 40.0;
double angle_threshold = -1.0472;

auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_TRUE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = 1.0472;

auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_TRUE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_TRUE(node->isNoise(object));
}
}

{
auto velocity = tier4_autoware_utils::createVector3(40.0, 30.0, 0.0);
auto position = tier4_autoware_utils::createPoint(1.0, 2.0, 0.0);
auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0);
auto object = get_object(velocity, position, orientation);
{
double velocity_threshold = 40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = 40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
}

{
auto velocity = tier4_autoware_utils::createVector3(24.0, 18.0, 0.0);
auto position = tier4_autoware_utils::createPoint(1.0, 0.0, 0.0);
auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0);
auto object = get_object(velocity, position, orientation);
{
double velocity_threshold = 40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = 40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_TRUE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_TRUE(node->isNoise(object));
}
}

{
auto velocity = tier4_autoware_utils::createVector3(24.0, 18.0, 0.0);
auto position = tier4_autoware_utils::createPoint(1.0, 2.0, 0.0);
auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0);
auto object = get_object(velocity, position, orientation);
{
double velocity_threshold = 40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = 40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = 1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
{
double velocity_threshold = -40.0;
double angle_threshold = -1.0472;
auto node = get_node(angle_threshold, velocity_threshold);
EXPECT_FALSE(node->isNoise(object));
}
}
}
1 change: 1 addition & 0 deletions perception/tensorrt_yolox/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -114,4 +114,5 @@ endif()

ament_auto_package(INSTALL_TO_SHARE
launch
config
)
15 changes: 15 additions & 0 deletions perception/tensorrt_yolox/config/yolox_s_plus_opt.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
model_path: "$(var data_path)/tensorrt_yolox/$(var model_name).onnx"
label_path: "$(var data_path)/tensorrt_yolox/label.txt"
score_threshold: 0.35
nms_threshold: 0.7
precision: "int8" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8].
calibration_algorithm: "Entropy" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax].
dla_core_id: -1 # If positive ID value is specified, the node assign inference task to the DLA core.
quantize_first_layer: false # If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8.
quantize_last_layer: false # If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8.
profile_per_layer: false # If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose.
clip_value: 6.0 # If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration.
preprocess_on_gpu: true # If true, pre-processing is performed on GPU.
calibration_image_list_path: "" # Path to a file which contains path to images. Those images will be used for int8 quantization.
15 changes: 15 additions & 0 deletions perception/tensorrt_yolox/config/yolox_tiny.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
model_path: "$(var data_path)/tensorrt_yolox/$(var model_name).onnx"
label_path: "$(var data_path)/tensorrt_yolox/label.txt"
score_threshold: 0.35
nms_threshold: 0.7
precision: "fp16" # Operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8].
calibration_algorithm: "MinMax" # Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax].
dla_core_id: -1 # If positive ID value is specified, the node assign inference task to the DLA core.
quantize_first_layer: false # If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8.
quantize_last_layer: false # If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8.
profile_per_layer: false # If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose.
clip_value: 0.0 # If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration.
preprocess_on_gpu: true # If true, pre-processing is performed on GPU.
calibration_image_list_path: "" # Path to a file which contains path to images. Those images will be used for int8 quantization.
39 changes: 2 additions & 37 deletions perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,30 +5,7 @@
<arg name="output/objects" default="/perception/object_recognition/detection/rois0"/>
<arg name="model_name" default="yolox-sPlus-T4-960x960-pseudo-finetune"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="model_path" default="$(var data_path)/tensorrt_yolox"/>
<arg name="score_threshold" default="0.35"/>
<arg name="nms_threshold" default="0.7"/>
<arg name="precision" default="int8" description="operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8]"/>
<arg
name="calibration_algorithm"
default="Entropy"
description="Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]"
/>
<arg name="dla_core_id" default="-1" description="If positive ID value is specified, the node assign inference task to the DLA core"/>
<arg name="quantize_first_layer" default="false" description="If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8"/>
<arg name="quantize_last_layer" default="false" description="If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8"/>
<arg
name="profile_per_layer"
default="false"
description="If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose."
/>
<arg
name="clip_value"
default="6.0"
description="If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration."
/>
<arg name="preprocess_on_gpu" default="true" description="If true, pre-processing is performed on GPU"/>
<arg name="calibration_image_list_path" default="" description="Path to a file which contains path to images. Those images will be used for int8 quantization."/>
<arg name="yolox_param_path" default="$(find-pkg-share tensorrt_yolox)/config/yolox_s_plus_opt.param.yaml"/>
<arg name="use_decompress" default="true" description="use image decompress"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>

Expand All @@ -40,19 +17,7 @@
<node pkg="tensorrt_yolox" exec="tensorrt_yolox_node_exe" name="tensorrt_yolox" output="screen">
<remap from="~/in/image" to="$(var input/image)"/>
<remap from="~/out/objects" to="$(var output/objects)"/>
<param name="score_threshold" value="$(var score_threshold)"/>
<param name="nms_threshold" value="$(var nms_threshold)"/>
<param name="model_path" value="$(var model_path)/$(var model_name).onnx"/>
<param name="label_path" value="$(var model_path)/label.txt"/>
<param name="precision" value="$(var precision)"/>
<param name="calibration_algorithm" value="$(var calibration_algorithm)"/>
<param name="dla_core_id" value="$(var dla_core_id)"/>
<param name="quantize_first_layer" value="$(var quantize_first_layer)"/>
<param name="quantize_last_layer" value="$(var quantize_last_layer)"/>
<param name="profile_per_layer" value="$(var profile_per_layer)"/>
<param name="clip_value" value="$(var clip_value)"/>
<param name="preprocess_on_gpu" value="$(var preprocess_on_gpu)"/>
<param name="calibration_image_list_path" value="$(var calibration_image_list_path)"/>
<param from="$(var yolox_param_path)" allow_substs="true"/>
<param name="build_only" value="$(var build_only)"/>
</node>
</launch>
39 changes: 2 additions & 37 deletions perception/tensorrt_yolox/launch/yolox_tiny.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,30 +4,7 @@
<arg name="output/objects" default="/perception/object_recognition/detection/rois0"/>
<arg name="model_name" default="yolox-tiny"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="model_path" default="$(var data_path)/tensorrt_yolox"/>
<arg name="score_threshold" default="0.35"/>
<arg name="nms_threshold" default="0.7"/>
<arg name="precision" default="fp16" description="operation precision to be used on inference. Valid value is one of: [fp32, fp16, int8]"/>
<arg
name="calibration_algorithm"
default="MinMax"
description="Calibration algorithm to be used for quantization when precision==int8. Valid value is one of: [Entropy, (Legacy | Percentile), MinMax]"
/>
<arg name="dla_core_id" default="-1" description="If positive ID value is specified, the node assign inference task to the DLA core"/>
<arg name="quantize_first_layer" default="false" description="If true, set the operating precision for the first (input) layer to be fp16. This option is valid only when precision==int8"/>
<arg name="quantize_last_layer" default="false" description="If true, set the operating precision for the last (output) layer to be fp16. This option is valid only when precision==int8"/>
<arg
name="profile_per_layer"
default="false"
description="If true, profiler function will be enabled. Since the profile function may affect execution speed, it is recommended to set this flag true only for development purpose."
/>
<arg
name="clip_value"
default="0.0"
description="If positive value is specified, the value of each layer output will be clipped between [0.0, clip_value]. This option is valid only when precision==int8 and used to manually specify the dynamic range instead of using any calibration."
/>
<arg name="preprocess_on_gpu" default="true" description="If true, pre-processing is performed on GPU"/>
<arg name="calibration_image_list_path" default="" description="Path to a file which contains path to images. Those images will be used for int8 quantization."/>
<arg name="yolox_param_path" default="$(find-pkg-share tensorrt_yolox)/config/yolox_tiny.param.yaml"/>
<arg name="use_decompress" default="true" description="use image decompress"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>

Expand All @@ -39,19 +16,7 @@
<node pkg="tensorrt_yolox" exec="tensorrt_yolox_node_exe" name="tensorrt_yolox" output="screen">
<remap from="~/in/image" to="$(var input/image)"/>
<remap from="~/out/objects" to="$(var output/objects)"/>
<param name="score_threshold" value="$(var score_threshold)"/>
<param name="nms_threshold" value="$(var nms_threshold)"/>
<param name="model_path" value="$(var model_path)/$(var model_name).onnx"/>
<param name="label_path" value="$(var model_path)/label.txt"/>
<param name="precision" value="$(var precision)"/>
<param name="calibration_algorithm" value="$(var calibration_algorithm)"/>
<param name="dla_core_id" value="$(var dla_core_id)"/>
<param name="quantize_first_layer" value="$(var quantize_first_layer)"/>
<param name="quantize_last_layer" value="$(var quantize_last_layer)"/>
<param name="profile_per_layer" value="$(var profile_per_layer)"/>
<param name="clip_value" value="$(var clip_value)"/>
<param name="preprocess_on_gpu" value="$(var preprocess_on_gpu)"/>
<param name="calibration_image_list_path" value="$(var calibration_image_list_path)"/>
<param from="$(var yolox_param_path)" allow_substs="true"/>
<param name="build_only" value="$(var build_only)"/>
</node>
</launch>
Loading