Skip to content

Commit

Permalink
ci(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Nov 5, 2022
1 parent eb5126a commit b6a0880
Show file tree
Hide file tree
Showing 10 changed files with 969 additions and 1,185 deletions.
10 changes: 2 additions & 8 deletions common/autoware_auto_geometry/test/src/test_area.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,7 @@ class AreaTest : public ::testing::Test
using Point = typename DataStructure::value_type;
using Real = decltype(autoware::common::geometry::point_adapter::x_(std::declval<Point>()));

auto area()
{
return autoware::common::geometry::area_checked_2d(data_.begin(), data_.end());
}
auto area() { return autoware::common::geometry::area_checked_2d(data_.begin(), data_.end()); }

void add_point(Real x, Real y)
{
Expand All @@ -56,10 +53,7 @@ using TestTypes = TestTypes_<geometry_msgs::msg::Point32>;
TYPED_TEST_SUITE(AreaTest, TestTypes, );

// The empty set has zero area
TYPED_TEST(AreaTest, DegenerateZero)
{
EXPECT_FLOAT_EQ(0.0, this->area());
}
TYPED_TEST(AreaTest, DegenerateZero) { EXPECT_FLOAT_EQ(0.0, this->area()); }

// An individual point has zero area
TYPED_TEST(AreaTest, DegenerateOne)
Expand Down
118 changes: 60 additions & 58 deletions common/autoware_auto_geometry/test/src/test_common_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,20 +38,18 @@ T make_points(const float x, const float y)
}

// PointTypes to be tested
using PointTypes = ::testing::Types<geometry_msgs::msg::Point32, autoware::common::types::PointXYZIF>;
using PointTypes =
::testing::Types<geometry_msgs::msg::Point32, autoware::common::types::PointXYZIF>;

// Wrapper function for stubbing output of
// autoware::common::geometry::check_point_position_to_line_2d
template <typename T>
int point_position_checker(const T& p1, const T& p2, const T& q)
int point_position_checker(const T & p1, const T & p2, const T & q)
{
auto result = autoware::common::geometry::check_point_position_to_line_2d(p1, p2, q);
if (result > 0.0F)
{
if (result > 0.0F) {
return 1;
}
else if (result < 0.0F)
{
} else if (result < 0.0F) {
return -1;
}
return result;
Expand All @@ -75,21 +73,22 @@ struct PointPositionToLine : public ::testing::Test
TYPED_TEST_SUITE_P(PointPositionToLine);

template <typename T>
std::vector<std::pair<typename PointPositionToLine<T>::Parameters, int>> PointPositionToLine<T>::input_output{
{ { make_points<T>(0.0F, 0.0F), make_points<T>(-1.0F, 1.0F), make_points<T>(1.0F, 5.0F) }, -1 },
{ { make_points<T>(0.0F, 0.0F), make_points<T>(-1.0F, 1.0F), make_points<T>(-1.0F, 0.5F) }, 1 },
// Check point on the line
{ { make_points<T>(0.0F, 0.0F), make_points<T>(-1.0F, 1.0F), make_points<T>(-2.0F, 2.0F) }, 0 },
};
std::vector<std::pair<typename PointPositionToLine<T>::Parameters, int>>
PointPositionToLine<T>::input_output{
{{make_points<T>(0.0F, 0.0F), make_points<T>(-1.0F, 1.0F), make_points<T>(1.0F, 5.0F)}, -1},
{{make_points<T>(0.0F, 0.0F), make_points<T>(-1.0F, 1.0F), make_points<T>(-1.0F, 0.5F)}, 1},
// Check point on the line
{{make_points<T>(0.0F, 0.0F), make_points<T>(-1.0F, 1.0F), make_points<T>(-2.0F, 2.0F)}, 0},
};

TYPED_TEST_P(PointPositionToLine, PointPositionToLineTest)
{
for (size_t i = 0; i < PointPositionToLine<TypeParam>::input_output.size(); ++i)
{
const auto& input = PointPositionToLine<TypeParam>::input_output[i].first;
EXPECT_EQ(point_position_checker(input.p1, input.p2, input.q),
PointPositionToLine<TypeParam>::input_output[i].second)
<< "Index " << i;
for (size_t i = 0; i < PointPositionToLine<TypeParam>::input_output.size(); ++i) {
const auto & input = PointPositionToLine<TypeParam>::input_output[i].first;
EXPECT_EQ(
point_position_checker(input.p1, input.p2, input.q),
PointPositionToLine<TypeParam>::input_output[i].second)
<< "Index " << i;
}
}

Expand Down Expand Up @@ -118,36 +117,36 @@ TYPED_TEST_SUITE_P(InsidePolygon);
template <typename T>
std::vector<std::pair<typename InsidePolygon<T>::Parameters, bool>> InsidePolygon<T>::input_output{
// point inside the rectangle
{ { { make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F) },
make_points<T>(0.F, 0.5F) },
true },
{{{make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F)},
make_points<T>(0.F, 0.5F)},
true},
// point below the rectangle
{ { { make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F) },
make_points<T>(0.5F, 0.F) },
false },
{{{make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F)},
make_points<T>(0.5F, 0.F)},
false},
// point above the rectangle
{ { { make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F) },
make_points<T>(0.5F, 1.75F) },
false },
{{{make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F)},
make_points<T>(0.5F, 1.75F)},
false},
// point on the rectangle
{ { { make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F) },
make_points<T>(0.5F, 0.5F) },
true },
{{{make_points<T>(0.0F, 0.0F), make_points<T>(1.0F, 1.0F), make_points<T>(0.5F, 1.5F),
make_points<T>(-0.5F, 0.5F)},
make_points<T>(0.5F, 0.5F)},
true},
};

TYPED_TEST_P(InsidePolygon, InsidePolygonTest)
{
for (size_t i = 0; i < InsidePolygon<TypeParam>::input_output.size(); ++i)
{
const auto& input = InsidePolygon<TypeParam>::input_output[i].first;
for (size_t i = 0; i < InsidePolygon<TypeParam>::input_output.size(); ++i) {
const auto & input = InsidePolygon<TypeParam>::input_output[i].first;
EXPECT_EQ(
autoware::common::geometry::is_point_inside_polygon_2d(input.polygon.begin(), input.polygon.end(), input.q),
InsidePolygon<TypeParam>::input_output[i].second)
<< "Index " << i;
autoware::common::geometry::is_point_inside_polygon_2d(
input.polygon.begin(), input.polygon.end(), input.q),
InsidePolygon<TypeParam>::input_output[i].second)
<< "Index " << i;
}
}

Expand All @@ -162,34 +161,37 @@ TEST(ordered_check, basic)
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(8.0, 4.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(9.0, 1.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(3.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 5.0)
};
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 5.0)};
EXPECT_TRUE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end()));

// CCW
points_list = { make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 5.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(3.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(9.0, 1.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(8.0, 4.0) };
points_list = {
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 5.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(3.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(9.0, 1.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(8.0, 4.0)};
EXPECT_TRUE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end()));

// Unordered
points_list = { make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 5.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(3.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(8.0, 4.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(9.0, 1.0) };
points_list = {
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 5.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(3.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(8.0, 4.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(9.0, 1.0)};
EXPECT_FALSE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end()));

// Unordered
points_list = { make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(0.0, 0.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(1.0, 1.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(1.0, 0.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 1.0) };
points_list = {
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(0.0, 0.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(1.0, 1.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(1.0, 0.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 1.0)};
EXPECT_FALSE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end()));

// Collinearity
points_list = { make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(4.0, 4.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(6.0, 6.0) };
points_list = {
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(2.0, 2.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(4.0, 4.0),
make_points<autoware_auto_perception_msgs::msg::PointXYZIF>(6.0, 6.0)};
EXPECT_TRUE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end()));
}
54 changes: 21 additions & 33 deletions common/grid_map_utils/test/test_polygon_iterator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,7 @@ TEST(PolygonIterator, FullCover)
EXPECT_EQ(0, (*iterator)(0));
EXPECT_EQ(2, (*iterator)(1));

for (int i = 0; i < 37; ++i)
++iterator;
for (int i = 0; i < 37; ++i) ++iterator;

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(7, (*iterator)(0));
Expand All @@ -75,7 +74,7 @@ TEST(PolygonIterator, FullCover)
// Copied from grid_map::PolygonIterator
TEST(PolygonIterator, Outside)
{
GridMap map({ "types" });
GridMap map({"types"});
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)

Polygon polygon;
Expand All @@ -92,7 +91,7 @@ TEST(PolygonIterator, Outside)
// Copied from grid_map::PolygonIterator
TEST(PolygonIterator, Square)
{
GridMap map({ "types" });
GridMap map({"types"});
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)

Polygon polygon;
Expand Down Expand Up @@ -139,7 +138,7 @@ TEST(PolygonIterator, Square)
// Copied from grid_map::PolygonIterator
TEST(PolygonIterator, TopLeftTriangle)
{
GridMap map({ "types" });
GridMap map({"types"});
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)

Polygon polygon;
Expand All @@ -162,7 +161,7 @@ TEST(PolygonIterator, TopLeftTriangle)
// Copied from grid_map::PolygonIterator
TEST(PolygonIterator, MoveMap)
{
GridMap map({ "layer" });
GridMap map({"layer"});
map.setGeometry(Length(8.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)
map.move(Position(2.0, 0.0));

Expand All @@ -182,8 +181,7 @@ TEST(PolygonIterator, MoveMap)
EXPECT_EQ(6, (*iterator)(0));
EXPECT_EQ(2, (*iterator)(1));

for (int i = 0; i < 4; ++i)
++iterator;
for (int i = 0; i < 4; ++i) ++iterator;

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(7, (*iterator)(0));
Expand All @@ -194,8 +192,7 @@ TEST(PolygonIterator, MoveMap)
EXPECT_EQ(0, (*iterator)(0));
EXPECT_EQ(1, (*iterator)(1));

for (int i = 0; i < 8; ++i)
++iterator;
for (int i = 0; i < 8; ++i) ++iterator;

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(2, (*iterator)(0));
Expand All @@ -208,7 +205,7 @@ TEST(PolygonIterator, MoveMap)
// This test shows a difference when an edge passes exactly through the center of a cell
TEST(PolygonIterator, Difference)
{
GridMap map({ "layer" });
GridMap map({"layer"});
map.setGeometry(Length(5.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)

// Triangle where the hypotenuse is an exact diagonal of the map: difference.
Expand All @@ -219,15 +216,12 @@ TEST(PolygonIterator, Difference)
grid_map_utils::PolygonIterator iterator(map, polygon);
grid_map::PolygonIterator gm_iterator(map, polygon);
bool diff = false;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd())
{
if ((*gm_iterator)(0) != (*iterator)(0) || (*gm_iterator)(1) != (*iterator)(1))
diff = true;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd()) {
if ((*gm_iterator)(0) != (*iterator)(0) || (*gm_iterator)(1) != (*iterator)(1)) diff = true;
++iterator;
++gm_iterator;
}
if (iterator.isPastEnd() != gm_iterator.isPastEnd())
{
if (iterator.isPastEnd() != gm_iterator.isPastEnd()) {
diff = true;
}
EXPECT_TRUE(diff);
Expand All @@ -240,23 +234,20 @@ TEST(PolygonIterator, Difference)
iterator = grid_map_utils::PolygonIterator(map, polygon);
gm_iterator = grid_map::PolygonIterator(map, polygon);
diff = false;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd())
{
if ((*gm_iterator)(0) != (*iterator)(0) || (*gm_iterator)(1) != (*iterator)(1))
diff = true;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd()) {
if ((*gm_iterator)(0) != (*iterator)(0) || (*gm_iterator)(1) != (*iterator)(1)) diff = true;
++iterator;
++gm_iterator;
}
if (iterator.isPastEnd() != gm_iterator.isPastEnd())
{
if (iterator.isPastEnd() != gm_iterator.isPastEnd()) {
diff = true;
}
EXPECT_FALSE(diff);
}

TEST(PolygonIterator, SelfCrossingPolygon)
{
GridMap map({ "layer" });
GridMap map({"layer"});
map.setGeometry(Length(5.0, 5.0), 1.0, Position(0.0, 0.0)); // bufferSize(8, 5)

// Hour-glass shape
Expand All @@ -268,24 +259,21 @@ TEST(PolygonIterator, SelfCrossingPolygon)
grid_map_utils::PolygonIterator iterator(map, polygon);
grid_map::PolygonIterator gm_iterator(map, polygon);

const std::vector<Index> expected_indexes = { Index(0, 0), Index(0, 1), Index(0, 2), Index(0, 3), Index(0, 4),
Index(1, 1), Index(1, 2), Index(1, 3), Index(2, 2), Index(3, 2),
Index(4, 1), Index(4, 2), Index(4, 3) };
const std::vector<Index> expected_indexes = {
Index(0, 0), Index(0, 1), Index(0, 2), Index(0, 3), Index(0, 4), Index(1, 1), Index(1, 2),
Index(1, 3), Index(2, 2), Index(3, 2), Index(4, 1), Index(4, 2), Index(4, 3)};
bool diff = false;
size_t i = 0;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd())
{
if ((*gm_iterator)(0) != (*iterator)(0) || (*gm_iterator)(1) != (*iterator)(1))
diff = true;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd()) {
if ((*gm_iterator)(0) != (*iterator)(0) || (*gm_iterator)(1) != (*iterator)(1)) diff = true;
ASSERT_TRUE(i < expected_indexes.size());
EXPECT_EQ((*iterator)(0), expected_indexes[i](0));
EXPECT_EQ((*iterator)(1), expected_indexes[i](1));
++i;
++iterator;
++gm_iterator;
}
if (iterator.isPastEnd() != gm_iterator.isPastEnd())
{
if (iterator.isPastEnd() != gm_iterator.isPastEnd()) {
diff = true;
}
EXPECT_FALSE(diff);
Expand Down
2 changes: 1 addition & 1 deletion perception/elevation_map_loader/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ See <https://pointclouds.org/documentation/tutorials/statistical_outlier.html> f
| Name | Type | Description | Default value |
| :--------------------------------------------------------- | :---- | :----------------------------------------------------------------------------- | :------------ |
| pcl_grid_map_extraction/outlier_removal/is_remove_outliers | float | Whether to perform statistical outlier removal. | false |
| pcl_grid_map_extraction/outlier_removal/mean_K | float | Number of neighbors to analyze for estimating statistics of a point. | 10 |
| pcl_grid_map_extraction/outlier_removal/mean_K | float | Number of neighbors to analyze for estimating statistics of a point. | 10 |
| pcl_grid_map_extraction/outlier_removal/stddev_threshold | float | Number of standard deviations under which points are considered to be inliers. | 1.0 |

#### Subsampling parameters
Expand Down
Loading

0 comments on commit b6a0880

Please sign in to comment.