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

refactor(grid_map_utils): add autoware prefix and namespace #7487

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
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ common/geography_utils/** koji.minoda@tier4.jp
common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp
common/glog_component/** takamasa.horibe@tier4.jp
common/goal_distance_calculator/** taiki.tanaka@tier4.jp
common/grid_map_utils/** maxime.clement@tier4.jp
common/autoware_grid_map_utils/** maxime.clement@tier4.jp
common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp
common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp
common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
Expand Down
2 changes: 1 addition & 1 deletion common/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ nav:
- 'Common Libraries':
- 'autoware_auto_common':
- 'comparisons': common/autoware_auto_common/design/comparisons
- 'autoware_grid_map_utils': common/autoware_grid_map_utils
- 'autoware_point_types': common/autoware_point_types
- 'Cuda Utils': common/cuda_utils
- 'Geography Utils': common/geography_utils
- 'Global Parameter Loader': common/global_parameter_loader/Readme
- 'Glog Component': common/glog_component
- 'grid_map_utils': common/grid_map_utils
- 'interpolation': common/interpolation
- 'Kalman Filter': common/kalman_filter
- 'Motion Utils': common/motion_utils
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.5)
project(grid_map_utils)
project(autoware_grid_map_utils)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,18 +19,18 @@ More details on the scan line algorithm can be found in the References.

## API

The `grid_map_utils::PolygonIterator` follows the same API as the original [`grid_map::PolygonIterator`](https://docs.ros.org/en/kinetic/api/grid_map_core/html/classgrid__map_1_1PolygonIterator.html).
The `autoware::grid_map_utils::PolygonIterator` follows the same API as the original [`grid_map::PolygonIterator`](https://docs.ros.org/en/kinetic/api/grid_map_core/html/classgrid__map_1_1PolygonIterator.html).

## Assumptions

The behavior of the `grid_map_utils::PolygonIterator` is only guaranteed to match the `grid_map::PolygonIterator` if edges of the polygon do not _exactly_ cross any cell center.
The behavior of the `autoware::grid_map_utils::PolygonIterator` is only guaranteed to match the `grid_map::PolygonIterator` if edges of the polygon do not _exactly_ cross any cell center.
In such a case, whether the crossed cell is considered inside or outside of the polygon can vary due to floating precision error.

## Performances

Benchmarking code is implemented in `test/benchmarking.cpp` and is also used to validate that the `grid_map_utils::PolygonIterator` behaves exactly like the `grid_map::PolygonIterator`.
Benchmarking code is implemented in `test/benchmarking.cpp` and is also used to validate that the `autoware::grid_map_utils::PolygonIterator` behaves exactly like the `grid_map::PolygonIterator`.

The following figure shows a comparison of the runtime between the implementation of this package (`grid_map_utils`) and the original implementation (`grid_map`).
The following figure shows a comparison of the runtime between the implementation of this package (`autoware_grid_map_utils`) and the original implementation (`grid_map`).
The time measured includes the construction of the iterator and the iteration over all indexes and is shown using a logarithmic scale.
Results were obtained varying the side size of a square grid map with `100 <= n <= 1000` (size=`n` means a grid of `n x n` cells),
random polygons with a number of vertices `3 <= m <= 100` and with each parameter `(n,m)` repeated 10 times.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef GRID_MAP_UTILS__POLYGON_ITERATOR_HPP_
#define GRID_MAP_UTILS__POLYGON_ITERATOR_HPP_
#ifndef AUTOWARE_GRID_MAP_UTILS__POLYGON_ITERATOR_HPP_
#define AUTOWARE_GRID_MAP_UTILS__POLYGON_ITERATOR_HPP_

#include "grid_map_core/TypeDefs.hpp"

Expand All @@ -24,7 +24,7 @@
#include <utility>
#include <vector>

namespace grid_map_utils
namespace autoware::grid_map_utils
{

/// @brief Representation of a polygon edge made of 2 vertices
Expand Down Expand Up @@ -124,6 +124,6 @@ class PolygonIterator
int current_col_;
int current_to_col_;
};
} // namespace grid_map_utils
} // namespace autoware::grid_map_utils

#endif // GRID_MAP_UTILS__POLYGON_ITERATOR_HPP_
#endif // AUTOWARE_GRID_MAP_UTILS__POLYGON_ITERATOR_HPP_
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>grid_map_utils</name>
<name>autoware_grid_map_utils</name>
<version>0.0.0</version>
<description>Utilities for the grid_map library</description>
<maintainer email="maxime.clement@tier4.jp">Maxime CLEMENT</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "grid_map_utils/polygon_iterator.hpp"
#include "autoware_grid_map_utils/polygon_iterator.hpp"

#include "grid_map_core/GridMap.hpp"
#include "grid_map_core/Polygon.hpp"
Expand All @@ -22,7 +22,7 @@
#include <functional>
#include <utility>

namespace grid_map_utils
namespace autoware::grid_map_utils
{

std::vector<Edge> PolygonIterator::calculateSortedEdges(const grid_map::Polygon & polygon)
Expand Down Expand Up @@ -214,4 +214,4 @@ PolygonIterator & PolygonIterator::operator++()
{
return current_line_ >= intersections_per_line_.size();
}
} // namespace grid_map_utils
} // namespace autoware::grid_map_utils
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_grid_map_utils/polygon_iterator.hpp"
#include "grid_map_core/TypeDefs.hpp"
#include "grid_map_cv/GridMapCvConverter.hpp"
#include "grid_map_cv/GridMapCvProcessing.hpp"
#include "grid_map_utils/polygon_iterator.hpp"

#include <grid_map_core/iterators/PolygonIterator.hpp>
#include <grid_map_cv/grid_map_cv.hpp>
Expand Down Expand Up @@ -116,7 +116,7 @@ int main(int argc, char * argv[])
polygon.addVertex(base_polygon.getVertex(idx) + offset);
}
stopwatch.tic("gmu_ctor");
grid_map_utils::PolygonIterator grid_map_utils_iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator grid_map_utils_iterator(map, polygon);
grid_map_utils_constructor_duration += stopwatch.toc("gmu_ctor");
stopwatch.tic("gm_ctor");
grid_map::PolygonIterator grid_map_iterator(map, polygon);
Expand All @@ -143,8 +143,8 @@ int main(int argc, char * argv[])
if (diff || visualize) {
// Prepare images of the cells selected by the two PolygonIterators
auto gridmap = map;
for (grid_map_utils::PolygonIterator iterator(map, polygon); !iterator.isPastEnd();
++iterator)
for (autoware::grid_map_utils::PolygonIterator iterator(map, polygon);
!iterator.isPastEnd(); ++iterator)
map.at("layer", *iterator) = 100;
for (grid_map::PolygonIterator iterator(gridmap, polygon); !iterator.isPastEnd();
++iterator)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "grid_map_utils/polygon_iterator.hpp"
#include "autoware_grid_map_utils/polygon_iterator.hpp"

#include <grid_map_core/iterators/PolygonIterator.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>
Expand Down Expand Up @@ -45,7 +45,7 @@ TEST(PolygonIterator, FullCover)
polygon.addVertex(Position(100.0, -100.0));
polygon.addVertex(Position(-100.0, -100.0));

grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(0, (*iterator)(0));
Expand Down Expand Up @@ -83,7 +83,7 @@ TEST(PolygonIterator, Outside)
polygon.addVertex(Position(101.0, 99.0));
polygon.addVertex(Position(99.0, 99.0));

grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);

EXPECT_TRUE(iterator.isPastEnd());
}
Expand All @@ -100,7 +100,7 @@ TEST(PolygonIterator, Square)
polygon.addVertex(Position(1.0, -1.5));
polygon.addVertex(Position(-1.0, -1.5));

grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(3, (*iterator)(0));
Expand Down Expand Up @@ -146,7 +146,7 @@ TEST(PolygonIterator, TopLeftTriangle)
polygon.addVertex(Position(40.1, 20.4));
polygon.addVertex(Position(-40.1, -20.6));

grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(0, (*iterator)(0));
Expand All @@ -170,7 +170,7 @@ TEST(PolygonIterator, MoveMap)
polygon.addVertex(Position(0.9, 1.6));
polygon.addVertex(Position(0.9, -1.6));
polygon.addVertex(Position(6.1, -1.6));
grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);

EXPECT_FALSE(iterator.isPastEnd());
EXPECT_EQ(6, (*iterator)(0));
Expand Down Expand Up @@ -213,7 +213,7 @@ TEST(PolygonIterator, Difference)
polygon.addVertex(Position(2.5, 2.5));
polygon.addVertex(Position(-2.5, 2.5));
polygon.addVertex(Position(-2.5, -2.5));
grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);
grid_map::PolygonIterator gm_iterator(map, polygon);
bool diff = false;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd()) {
Expand All @@ -231,7 +231,7 @@ TEST(PolygonIterator, Difference)
polygon.addVertex(Position(2.5, 2.1));
polygon.addVertex(Position(-2.5, 2.5));
polygon.addVertex(Position(-2.5, -2.9));
iterator = grid_map_utils::PolygonIterator(map, polygon);
iterator = autoware::grid_map_utils::PolygonIterator(map, polygon);
gm_iterator = grid_map::PolygonIterator(map, polygon);
diff = false;
while (!iterator.isPastEnd() && !gm_iterator.isPastEnd()) {
Expand All @@ -256,7 +256,7 @@ TEST(PolygonIterator, SelfCrossingPolygon)
polygon.addVertex(Position(2.5, -2.9));
polygon.addVertex(Position(-2.5, 2.5));
polygon.addVertex(Position(-2.5, -2.5));
grid_map_utils::PolygonIterator iterator(map, polygon);
autoware::grid_map_utils::PolygonIterator iterator(map, polygon);
grid_map::PolygonIterator gm_iterator(map, polygon);

const std::vector<Index> expected_indexes = {
Expand Down
2 changes: 1 addition & 1 deletion perception/elevation_map_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_grid_map_utils</depend>
<depend>autoware_map_msgs</depend>
<depend>grid_map_cv</depend>
<depend>grid_map_pcl</depend>
<depend>grid_map_ros</depend>
<depend>grid_map_utils</depend>
<depend>lanelet2_extension</depend>
<depend>libpcl-all-dev</depend>
<depend>pcl_conversions</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@

#include "elevation_map_loader/elevation_map_loader_node.hpp"

#include <autoware_grid_map_utils/polygon_iterator.hpp>
#include <grid_map_core/GridMap.hpp>
#include <grid_map_cv/InpaintFilter.hpp>
#include <grid_map_pcl/GridMapPclLoader.hpp>
#include <grid_map_pcl/helpers.hpp>
#include <grid_map_ros/GridMapRosConverter.hpp>
#include <grid_map_utils/polygon_iterator.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <rclcpp/logger.hpp>
Expand Down Expand Up @@ -382,8 +382,8 @@ void ElevationMapLoaderNode::inpaintElevationMap(const float radius)
for (const auto & p : lane_polygon) {
polygon.addVertex(grid_map::Position(p[0], p[1]));
}
for (grid_map_utils::PolygonIterator iterator(elevation_map_, polygon); !iterator.isPastEnd();
++iterator) {
for (autoware::grid_map_utils::PolygonIterator iterator(elevation_map_, polygon);
!iterator.isPastEnd(); ++iterator) {
if (!elevation_map_.isValid(*iterator, layer_name_)) {
elevation_map_.at("inpaint_mask", *iterator) = 1.0;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_grid_map_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
Expand All @@ -30,7 +31,6 @@
<depend>geometry_msgs</depend>
<depend>grid_map_core</depend>
<depend>grid_map_ros</depend>
<depend>grid_map_utils</depend>
<depend>interpolation</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@

#include "autoware_behavior_velocity_crosswalk_module/util.hpp"

#include <autoware_grid_map_utils/polygon_iterator.hpp>
#include <grid_map_ros/GridMapRosConverter.hpp>
#include <grid_map_utils/polygon_iterator.hpp>

#include <algorithm>
#include <vector>
Expand Down Expand Up @@ -129,7 +129,8 @@ void clear_occlusions_behind_objects(
polygon_to_clear.addVertex(
interpolate_point({grid_map_position, edge_points.back()}, 10.0 * range));
polygon_to_clear.addVertex(edge_points.back());
for (grid_map_utils::PolygonIterator it(grid_map, polygon_to_clear); !it.isPastEnd(); ++it)
for (autoware::grid_map_utils::PolygonIterator it(grid_map, polygon_to_clear);
!it.isPastEnd(); ++it)
grid_map.at("layer", *it) = 0;
}
}
Expand All @@ -156,7 +157,7 @@ bool is_crosswalk_occluded(
crosswalk_lanelet, {path_intersection.x, path_intersection.y}, detection_range)) {
grid_map::Polygon poly;
for (const auto & p : detection_area) poly.addVertex(grid_map::Position(p.x(), p.y()));
for (grid_map_utils::PolygonIterator iter(grid_map, poly); !iter.isPastEnd(); ++iter)
for (autoware::grid_map_utils::PolygonIterator iter(grid_map, poly); !iter.isPastEnd(); ++iter)
if (is_occluded(grid_map, min_nb_of_cells, *iter, params)) return true;
}
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,13 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_grid_map_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>geometry_msgs</depend>
<depend>grid_map_ros</depend>
<depend>grid_map_utils</depend>
<depend>interpolation</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ void findOcclusionSpots(
for (const auto & point : polygon.outer()) {
grid_polygon.addVertex({point.x(), point.y()});
}
for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd();
++iterator) {
for (autoware::grid_map_utils::PolygonIterator iterator(grid, grid_polygon);
!iterator.isPastEnd(); ++iterator) {
const grid_map::Index & index = *iterator;
if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::UNKNOWN) {
grid_map::Position occlusion_spot_position;
Expand All @@ -77,8 +77,8 @@ bool isCollisionFree(
for (const auto & point : polygon.outer()) {
grid_polygon.addVertex({point.x(), point.y()});
}
for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd();
++iterator) {
for (autoware::grid_map_utils::PolygonIterator iterator(grid, grid_polygon);
!iterator.isPastEnd(); ++iterator) {
const grid_map::Index & index = *iterator;
if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) {
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

#include <autoware_behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
#include <autoware_behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware_grid_map_utils/polygon_iterator.hpp>
#include <grid_map_core/GridMap.hpp>
#include <grid_map_core/iterators/LineIterator.hpp>
#include <grid_map_ros/GridMapRosConverter.hpp>
#include <grid_map_utils/polygon_iterator.hpp>
#include <opencv2/opencv.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/math/normalization.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ TEST(compareTime, polygon_vs_line_iterator)
for (const auto & point : polygon.outer()) {
grid_polygon.addVertex({point.x(), point.y()});
}
for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd();
++iterator) {
for (autoware::grid_map_utils::PolygonIterator iterator(grid, grid_polygon);
!iterator.isPastEnd(); ++iterator) {
const grid_map::Index & index = *iterator;
if (grid_data(index.x(), index.y()) == OCCUPIED) {
std::cout << "occupied" << std::endl;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ Obstacles from the lanelet map are not impacted by the masks.

#### Occupancy Grid

Masking is performed by iterating through the cells inside each polygon mask using the [`grid_map_utils::PolygonIterator`](https://github.com/autowarefoundation/autoware.universe/tree/main/common/grid_map_utils) function.
Masking is performed by iterating through the cells inside each polygon mask using the [`autoware::grid_map_utils::PolygonIterator`](https://github.com/autowarefoundation/autoware.universe/tree/main/common/autoware_grid_map_utils) function.
A threshold is then applied to only keep cells with an occupancy value above parameter `obstacles.occupancy_grid_threshold`.
Finally, the image is converted to an image and obstacle linestrings are extracted using the opencv function
[`findContour`](https://docs.opencv.org/3.4/d3/dc0/group__imgproc__shape.html#ga17ed9f5d79ae97bd4c7cf18403e1689a).
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_grid_map_utils</depend>
<depend>autoware_motion_velocity_planner_common</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
Expand All @@ -19,7 +20,6 @@
<depend>eigen</depend>
<depend>grid_map_msgs</depend>
<depend>grid_map_ros</depend>
<depend>grid_map_utils</depend>
<depend>lanelet2_core</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
Expand Down
Loading
Loading