Skip to content

Commit

Permalink
Finish renaming multi*_t -> multi_*_t
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
  • Loading branch information
maxime-clem committed Aug 10, 2023
1 parent b755ba7 commit 10cd778
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ void expandDrivableArea(
{
const auto uncrossable_lines =
extractUncrossableLines(*route_handler.getLaneletMapPtr(), params.avoid_linestring_types);
multilinestring_t uncrossable_lines_in_range;
multi_linestring_t uncrossable_lines_in_range;
const auto & p = path.points.front().point.pose.position;
for (const auto & line : uncrossable_lines)
if (boost::geometry::distance(line, point_t{p.x, p.y}) < params.max_path_arc_length)
Expand Down Expand Up @@ -63,7 +63,7 @@ Point convert_point(const point_t & p)
}

polygon_t createExpandedDrivableAreaPolygon(
const PathWithLaneId & path, const multipolygon_t & expansion_polygons)
const PathWithLaneId & path, const multi_polygon_t & expansion_polygons)
{
polygon_t original_da_poly;
original_da_poly.outer().reserve(path.left_bound.size() + path.right_bound.size() + 1);
Expand All @@ -72,7 +72,7 @@ polygon_t createExpandedDrivableAreaPolygon(
original_da_poly.outer().push_back(convert_point(*it));
original_da_poly.outer().push_back(original_da_poly.outer().front());

multipolygon_t unions;
multi_polygon_t unions;
auto expanded_da_poly = original_da_poly;
for (const auto & p : expansion_polygons) {
unions.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@ namespace drivable_area_expansion

double calculateDistanceLimit(
const linestring_t & base_ls, const polygon_t & expansion_polygon,
const multilinestring_t & limit_lines)
const multi_linestring_t & limit_lines)
{
auto dist_limit = std::numeric_limits<double>::max();
multipoint_t intersections;
multi_point_t intersections;
boost::geometry::intersection(expansion_polygon, limit_lines, intersections);
for (const auto & p : intersections)
dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls));
Expand All @@ -34,11 +34,11 @@ double calculateDistanceLimit(

double calculateDistanceLimit(
const linestring_t & base_ls, const polygon_t & expansion_polygon,
const multipolygon_t & limit_polygons)
const multi_polygon_t & limit_polygons)
{
auto dist_limit = std::numeric_limits<double>::max();
for (const auto & polygon : limit_polygons) {
multipoint_t intersections;
multi_point_t intersections;
boost::geometry::intersection(expansion_polygon, polygon, intersections);
for (const auto & p : intersections)
dist_limit = std::min(dist_limit, boost::geometry::distance(p, base_ls));
Expand All @@ -50,7 +50,7 @@ polygon_t createExpansionPolygon(
const linestring_t & base_ls, const double dist, const bool is_left_side)
{
namespace strategy = boost::geometry::strategy::buffer;
multipolygon_t polygons;
multi_polygon_t polygons;
// set a non 0 value for the buffer as it sometimes causes no polygon to be returned by bg:buffer
constexpr auto zero = 0.1;
const auto left_dist = is_left_side ? dist : zero;
Expand All @@ -66,7 +66,7 @@ std::array<double, 3> calculate_arc_length_range_and_distance(
const linestring_t & path_ls, const polygon_t & footprint, const linestring_t & bound,
const bool is_left, const double path_length)
{
multipoint_t intersections;
multi_point_t intersections;
double expansion_dist = 0.0;
double from_arc_length = std::numeric_limits<double>::max();
double to_arc_length = std::numeric_limits<double>::min();
Expand All @@ -93,7 +93,7 @@ std::array<double, 3> calculate_arc_length_range_and_distance(

polygon_t create_compensation_polygon(
const linestring_t & base_ls, const double compensation_dist, const bool is_left,
const multilinestring_t uncrossable_lines, const multipolygon_t & predicted_paths)
const multi_linestring_t uncrossable_lines, const multi_polygon_t & predicted_paths)
{
polygon_t compensation_polygon = createExpansionPolygon(base_ls, compensation_dist, !is_left);
double dist_limit = std::min(
Expand All @@ -106,9 +106,9 @@ polygon_t create_compensation_polygon(
return compensation_polygon;
}

multipolygon_t createExpansionPolygons(
const PathWithLaneId & path, const multipolygon_t & path_footprints,
const multipolygon_t & predicted_paths, const multilinestring_t & uncrossable_lines,
multi_polygon_t createExpansionPolygons(
const PathWithLaneId & path, const multi_polygon_t & path_footprints,
const multi_polygon_t & predicted_paths, const multi_linestring_t & uncrossable_lines,
const DrivableAreaExpansionParameters & params)
{
linestring_t path_ls;
Expand Down Expand Up @@ -143,7 +143,7 @@ multipolygon_t createExpansionPolygons(
}
const auto path_length = static_cast<double>(boost::geometry::length(path_ls));

multipolygon_t expansion_polygons;
multi_polygon_t expansion_polygons;
for (const auto & footprint : path_footprints) {
bool is_left = true;
for (const auto & bound : {left_ls, right_ls}) {
Expand Down Expand Up @@ -184,12 +184,12 @@ multipolygon_t createExpansionPolygons(
return expansion_polygons;
}

multipolygon_t createExpansionLaneletPolygons(
multi_polygon_t createExpansionLaneletPolygons(
const lanelet::ConstLanelets & path_lanes, const route_handler::RouteHandler & route_handler,
const multipolygon_t & path_footprints, const multipolygon_t & predicted_paths,
const multi_polygon_t & path_footprints, const multi_polygon_t & predicted_paths,
const DrivableAreaExpansionParameters & params)
{
multipolygon_t expansion_polygons;
multi_polygon_t expansion_polygons;
lanelet::ConstLanelets candidates;
const auto already_added = [&](const auto & ll) {
return std::find_if(candidates.begin(), candidates.end(), [&](const auto & l) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,11 @@ polygon_t createFootprint(const geometry_msgs::msg::Pose & pose, const polygon_t
return translatePolygon(rotatePolygon(base_footprint, angle), pose.position.x, pose.position.y);
}

multipolygon_t createObjectFootprints(
multi_polygon_t createObjectFootprints(
const autoware_auto_perception_msgs::msg::PredictedObjects & objects,
const DrivableAreaExpansionParameters & params)
{
multipolygon_t footprints;
multi_polygon_t footprints;
if (params.avoid_dynamic_objects) {
for (const auto & object : objects.objects) {
const auto front = object.shape.dimensions.x / 2 + params.dynamic_objects_extra_front_offset;
Expand All @@ -62,7 +62,7 @@ multipolygon_t createObjectFootprints(
return footprints;
}

multipolygon_t createPathFootprints(
multi_polygon_t createPathFootprints(
const PathWithLaneId & path, const DrivableAreaExpansionParameters & params)
{
const auto left = params.ego_left_offset + params.ego_extra_left_offset;
Expand All @@ -73,7 +73,7 @@ multipolygon_t createPathFootprints(
base_footprint.outer() = {
point_t{front, left}, point_t{front, right}, point_t{rear, right}, point_t{rear, left},
point_t{front, left}};
multipolygon_t footprints;
multi_polygon_t footprints;
// skip the last footprint as its orientation is usually wrong
footprints.reserve(path.points.size() - 1);
double arc_length = 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@

namespace drivable_area_expansion
{
multilinestring_t extractUncrossableLines(
multi_linestring_t extractUncrossableLines(
const lanelet::LaneletMap & lanelet_map, const std::vector<std::string> & uncrossable_types)
{
multilinestring_t lines;
multi_linestring_t lines;
linestring_t line;
for (const auto & ls : lanelet_map.lineStringLayer) {
if (hasTypes(ls, uncrossable_types)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -298,12 +298,12 @@ TEST(DrivableAreaExpansion, calculateDistanceLimit)
{
using drivable_area_expansion::calculateDistanceLimit;
using drivable_area_expansion::linestring_t;
using drivable_area_expansion::multilinestring_t;
using drivable_area_expansion::multi_linestring_t;
using drivable_area_expansion::polygon_t;

{
const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}};
const multilinestring_t uncrossable_lines = {};
const multi_linestring_t uncrossable_lines = {};
const polygon_t expansion_polygon = {
{{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}};
const auto limit_distance =
Expand All @@ -321,7 +321,7 @@ TEST(DrivableAreaExpansion, calculateDistanceLimit)
}
{
const linestring_t base_ls = {{0.0, 0.0}, {10.0, 0.0}};
const multilinestring_t uncrossable_lines = {
const multi_linestring_t uncrossable_lines = {
{{0.0, 2.0}, {10.0, 2.0}}, {{0.0, 1.5}, {10.0, 1.0}}};
const polygon_t expansion_polygon = {
{{0.0, -4.0}, {0.0, 4.0}, {10.0, 4.0}, {10.0, -4.0}, {10.0, -4.0}}, {}};
Expand Down

0 comments on commit 10cd778

Please sign in to comment.