|
| 1 | +// Copyright 2024 Tier IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp" |
| 16 | +#include "tier4_autoware_utils/geometry/geometry.hpp" |
| 17 | +#include "tier4_autoware_utils/math/unit_conversion.hpp" |
| 18 | + |
| 19 | +#include <geometry_msgs/msg/point32.hpp> |
| 20 | + |
| 21 | +#include <gtest/gtest.h> |
| 22 | + |
| 23 | +std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode> get_node( |
| 24 | + double angle_threshold, double velocity_threshold) |
| 25 | +{ |
| 26 | + rclcpp::NodeOptions node_options; |
| 27 | + |
| 28 | + node_options.parameter_overrides( |
| 29 | + {{"angle_threshold", angle_threshold}, {"velocity_threshold", velocity_threshold}}); |
| 30 | + auto node = |
| 31 | + std::make_shared<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode>( |
| 32 | + node_options); |
| 33 | + return node; |
| 34 | +} |
| 35 | + |
| 36 | +autoware_auto_perception_msgs::msg::DetectedObject get_object( |
| 37 | + geometry_msgs::msg::Vector3 velocity, geometry_msgs::msg::Point position, |
| 38 | + geometry_msgs::msg::Quaternion orientation) |
| 39 | +{ |
| 40 | + autoware_auto_perception_msgs::msg::DetectedObject object; |
| 41 | + object.kinematics.twist_with_covariance.twist.linear = velocity; |
| 42 | + object.kinematics.pose_with_covariance.pose.position = position; |
| 43 | + object.kinematics.pose_with_covariance.pose.orientation = orientation; |
| 44 | + return object; |
| 45 | +} |
| 46 | + |
| 47 | +TEST(RadarCrossingObjectsFilter, IsNoise) |
| 48 | +{ |
| 49 | + rclcpp::init(0, nullptr); |
| 50 | + { |
| 51 | + auto velocity = tier4_autoware_utils::createVector3(40.0, 30.0, 0.0); |
| 52 | + auto position = tier4_autoware_utils::createPoint(1.0, 0.0, 0.0); |
| 53 | + auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); |
| 54 | + auto object = get_object(velocity, position, orientation); |
| 55 | + { |
| 56 | + double velocity_threshold = 40.0; |
| 57 | + double angle_threshold = 1.0472; |
| 58 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 59 | + EXPECT_TRUE(node->isNoise(object)); |
| 60 | + } |
| 61 | + { |
| 62 | + double velocity_threshold = 40.0; |
| 63 | + double angle_threshold = -1.0472; |
| 64 | + |
| 65 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 66 | + EXPECT_TRUE(node->isNoise(object)); |
| 67 | + } |
| 68 | + { |
| 69 | + double velocity_threshold = -40.0; |
| 70 | + double angle_threshold = 1.0472; |
| 71 | + |
| 72 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 73 | + EXPECT_TRUE(node->isNoise(object)); |
| 74 | + } |
| 75 | + { |
| 76 | + double velocity_threshold = -40.0; |
| 77 | + double angle_threshold = -1.0472; |
| 78 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 79 | + EXPECT_TRUE(node->isNoise(object)); |
| 80 | + } |
| 81 | + } |
| 82 | + |
| 83 | + { |
| 84 | + auto velocity = tier4_autoware_utils::createVector3(40.0, 30.0, 0.0); |
| 85 | + auto position = tier4_autoware_utils::createPoint(1.0, 2.0, 0.0); |
| 86 | + auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); |
| 87 | + auto object = get_object(velocity, position, orientation); |
| 88 | + { |
| 89 | + double velocity_threshold = 40.0; |
| 90 | + double angle_threshold = 1.0472; |
| 91 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 92 | + EXPECT_FALSE(node->isNoise(object)); |
| 93 | + } |
| 94 | + { |
| 95 | + double velocity_threshold = 40.0; |
| 96 | + double angle_threshold = -1.0472; |
| 97 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 98 | + EXPECT_FALSE(node->isNoise(object)); |
| 99 | + } |
| 100 | + { |
| 101 | + double velocity_threshold = -40.0; |
| 102 | + double angle_threshold = 1.0472; |
| 103 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 104 | + EXPECT_FALSE(node->isNoise(object)); |
| 105 | + } |
| 106 | + { |
| 107 | + double velocity_threshold = -40.0; |
| 108 | + double angle_threshold = -1.0472; |
| 109 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 110 | + EXPECT_FALSE(node->isNoise(object)); |
| 111 | + } |
| 112 | + } |
| 113 | + |
| 114 | + { |
| 115 | + auto velocity = tier4_autoware_utils::createVector3(24.0, 18.0, 0.0); |
| 116 | + auto position = tier4_autoware_utils::createPoint(1.0, 0.0, 0.0); |
| 117 | + auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); |
| 118 | + auto object = get_object(velocity, position, orientation); |
| 119 | + { |
| 120 | + double velocity_threshold = 40.0; |
| 121 | + double angle_threshold = 1.0472; |
| 122 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 123 | + EXPECT_FALSE(node->isNoise(object)); |
| 124 | + } |
| 125 | + { |
| 126 | + double velocity_threshold = 40.0; |
| 127 | + double angle_threshold = -1.0472; |
| 128 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 129 | + EXPECT_FALSE(node->isNoise(object)); |
| 130 | + } |
| 131 | + { |
| 132 | + double velocity_threshold = -40.0; |
| 133 | + double angle_threshold = 1.0472; |
| 134 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 135 | + EXPECT_TRUE(node->isNoise(object)); |
| 136 | + } |
| 137 | + { |
| 138 | + double velocity_threshold = -40.0; |
| 139 | + double angle_threshold = -1.0472; |
| 140 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 141 | + EXPECT_TRUE(node->isNoise(object)); |
| 142 | + } |
| 143 | + } |
| 144 | + |
| 145 | + { |
| 146 | + auto velocity = tier4_autoware_utils::createVector3(24.0, 18.0, 0.0); |
| 147 | + auto position = tier4_autoware_utils::createPoint(1.0, 2.0, 0.0); |
| 148 | + auto orientation = tier4_autoware_utils::createQuaternion(1.0, 1.0, 1.0, 0.0); |
| 149 | + auto object = get_object(velocity, position, orientation); |
| 150 | + { |
| 151 | + double velocity_threshold = 40.0; |
| 152 | + double angle_threshold = 1.0472; |
| 153 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 154 | + EXPECT_FALSE(node->isNoise(object)); |
| 155 | + } |
| 156 | + { |
| 157 | + double velocity_threshold = 40.0; |
| 158 | + double angle_threshold = -1.0472; |
| 159 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 160 | + EXPECT_FALSE(node->isNoise(object)); |
| 161 | + } |
| 162 | + { |
| 163 | + double velocity_threshold = -40.0; |
| 164 | + double angle_threshold = 1.0472; |
| 165 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 166 | + EXPECT_FALSE(node->isNoise(object)); |
| 167 | + } |
| 168 | + { |
| 169 | + double velocity_threshold = -40.0; |
| 170 | + double angle_threshold = -1.0472; |
| 171 | + auto node = get_node(angle_threshold, velocity_threshold); |
| 172 | + EXPECT_FALSE(node->isNoise(object)); |
| 173 | + } |
| 174 | + } |
| 175 | +} |
0 commit comments