Skip to content

Commit 6fa23a4

Browse files
style(pre-commit): autofix
1 parent b8a5bb1 commit 6fa23a4

File tree

1 file changed

+25
-26
lines changed

1 file changed

+25
-26
lines changed

perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp

+25-26
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,12 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp"
1516
#include "tier4_autoware_utils/geometry/geometry.hpp"
1617
#include "tier4_autoware_utils/math/unit_conversion.hpp"
1718

1819
#include <geometry_msgs/msg/point32.hpp>
1920

20-
#include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp"
21-
2221
#include <gtest/gtest.h>
2322

2423
std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode> get_node(
@@ -35,16 +34,16 @@ std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFi
3534
}
3635

3736
autoware_auto_perception_msgs::msg::DetectedObject get_object(
38-
geometry_msgs::msg::Vector3 velocity, geometry_msgs::msg::Point position, 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;
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;
4545
}
4646

47-
4847
TEST(RadarCrossingObjectsFilter, IsNoise)
4948
{
5049
rclcpp::init(0, nullptr);
@@ -55,27 +54,27 @@ TEST(RadarCrossingObjectsFilter, IsNoise)
5554
auto object = get_object(velocity, position, orientation);
5655
{
5756
double velocity_threshold = 40.0;
58-
double angle_threshold = 1.0472;
57+
double angle_threshold = 1.0472;
5958
auto node = get_node(angle_threshold, velocity_threshold);
6059
EXPECT_TRUE(node->isNoise(object));
6160
}
6261
{
6362
double velocity_threshold = 40.0;
64-
double angle_threshold = -1.0472;
63+
double angle_threshold = -1.0472;
6564

6665
auto node = get_node(angle_threshold, velocity_threshold);
6766
EXPECT_TRUE(node->isNoise(object));
6867
}
6968
{
7069
double velocity_threshold = -40.0;
71-
double angle_threshold = 1.0472;
70+
double angle_threshold = 1.0472;
7271

7372
auto node = get_node(angle_threshold, velocity_threshold);
7473
EXPECT_TRUE(node->isNoise(object));
7574
}
7675
{
7776
double velocity_threshold = -40.0;
78-
double angle_threshold = -1.0472;
77+
double angle_threshold = -1.0472;
7978
auto node = get_node(angle_threshold, velocity_threshold);
8079
EXPECT_TRUE(node->isNoise(object));
8180
}
@@ -88,25 +87,25 @@ TEST(RadarCrossingObjectsFilter, IsNoise)
8887
auto object = get_object(velocity, position, orientation);
8988
{
9089
double velocity_threshold = 40.0;
91-
double angle_threshold = 1.0472;
90+
double angle_threshold = 1.0472;
9291
auto node = get_node(angle_threshold, velocity_threshold);
9392
EXPECT_FALSE(node->isNoise(object));
9493
}
9594
{
9695
double velocity_threshold = 40.0;
97-
double angle_threshold = -1.0472;
96+
double angle_threshold = -1.0472;
9897
auto node = get_node(angle_threshold, velocity_threshold);
9998
EXPECT_FALSE(node->isNoise(object));
10099
}
101100
{
102101
double velocity_threshold = -40.0;
103-
double angle_threshold = 1.0472;
102+
double angle_threshold = 1.0472;
104103
auto node = get_node(angle_threshold, velocity_threshold);
105104
EXPECT_FALSE(node->isNoise(object));
106105
}
107106
{
108107
double velocity_threshold = -40.0;
109-
double angle_threshold = -1.0472;
108+
double angle_threshold = -1.0472;
110109
auto node = get_node(angle_threshold, velocity_threshold);
111110
EXPECT_FALSE(node->isNoise(object));
112111
}
@@ -119,25 +118,25 @@ TEST(RadarCrossingObjectsFilter, IsNoise)
119118
auto object = get_object(velocity, position, orientation);
120119
{
121120
double velocity_threshold = 40.0;
122-
double angle_threshold = 1.0472;
121+
double angle_threshold = 1.0472;
123122
auto node = get_node(angle_threshold, velocity_threshold);
124123
EXPECT_FALSE(node->isNoise(object));
125124
}
126125
{
127126
double velocity_threshold = 40.0;
128-
double angle_threshold = -1.0472;
127+
double angle_threshold = -1.0472;
129128
auto node = get_node(angle_threshold, velocity_threshold);
130129
EXPECT_FALSE(node->isNoise(object));
131130
}
132131
{
133132
double velocity_threshold = -40.0;
134-
double angle_threshold = 1.0472;
133+
double angle_threshold = 1.0472;
135134
auto node = get_node(angle_threshold, velocity_threshold);
136135
EXPECT_TRUE(node->isNoise(object));
137136
}
138137
{
139138
double velocity_threshold = -40.0;
140-
double angle_threshold = -1.0472;
139+
double angle_threshold = -1.0472;
141140
auto node = get_node(angle_threshold, velocity_threshold);
142141
EXPECT_TRUE(node->isNoise(object));
143142
}
@@ -150,25 +149,25 @@ TEST(RadarCrossingObjectsFilter, IsNoise)
150149
auto object = get_object(velocity, position, orientation);
151150
{
152151
double velocity_threshold = 40.0;
153-
double angle_threshold = 1.0472;
152+
double angle_threshold = 1.0472;
154153
auto node = get_node(angle_threshold, velocity_threshold);
155154
EXPECT_FALSE(node->isNoise(object));
156155
}
157156
{
158157
double velocity_threshold = 40.0;
159-
double angle_threshold = -1.0472;
158+
double angle_threshold = -1.0472;
160159
auto node = get_node(angle_threshold, velocity_threshold);
161160
EXPECT_FALSE(node->isNoise(object));
162161
}
163162
{
164163
double velocity_threshold = -40.0;
165-
double angle_threshold = 1.0472;
164+
double angle_threshold = 1.0472;
166165
auto node = get_node(angle_threshold, velocity_threshold);
167166
EXPECT_FALSE(node->isNoise(object));
168167
}
169168
{
170169
double velocity_threshold = -40.0;
171-
double angle_threshold = -1.0472;
170+
double angle_threshold = -1.0472;
172171
auto node = get_node(angle_threshold, velocity_threshold);
173172
EXPECT_FALSE(node->isNoise(object));
174173
}

0 commit comments

Comments
 (0)