Skip to content

Commit

Permalink
refactor(occlusion_spot): boost::optional to std::optional (autowaref…
Browse files Browse the repository at this point in the history
…oundation#5832)

Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
Signed-off-by: karishma <karishma@interpl.ai>
  • Loading branch information
zulfaqar-azmi-t4 authored and karishma1911 committed Dec 19, 2023
1 parent db2bbb5 commit 389a89c
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ bool isCollisionFree(
return true;
}

boost::optional<Polygon2d> generateOcclusionPolygon(
std::optional<Polygon2d> generateOcclusionPolygon(
const Polygon2d & occupancy_poly, const Point2d & origin, const Point2d & min_theta_pos,
const Point2d & max_theta_pos, const double ray_max_length = 100.0)
{
Expand Down Expand Up @@ -157,7 +157,7 @@ boost::optional<Polygon2d> generateOcclusionPolygon(
occlusion_poly.outer().emplace_back(max_intersections.front());
}
//! case outside detection area
if (occlusion_poly.outer().size() == 2) return boost::none;
if (occlusion_poly.outer().size() == 2) return std::nullopt;
boost::geometry::correct(occlusion_poly);
Polygon2d hull_poly;
boost::geometry::convex_hull(occlusion_poly, hull_poly);
Expand Down Expand Up @@ -200,7 +200,7 @@ std::pair<size_t, size_t> calcEdgePoint(const Polygon2d & foot_print, const Poin
return std::make_pair(min_idx, max_idx);
}

boost::optional<Polygon2d> generateOccupiedPolygon(
std::optional<Polygon2d> generateOccupiedPolygon(
const Polygon2d & occupancy_poly, const Polygon2d & foot_print, const Point & position)
{
Point2d origin = {position.x, position.y};
Expand Down Expand Up @@ -275,9 +275,9 @@ void generateOccupiedImage(
for (const auto & foot_print : moving_vehicle_foot_prints) {
// calculate occlusion polygon from moving vehicle
const auto polys = generateOccupiedPolygon(occupancy_poly, foot_print, scan_origin);
if (polys == boost::none) continue;
if (polys == std::nullopt) continue;
// transform to cv point and stuck it to cv polygon
for (const auto & p : polys.get().outer()) {
for (const auto & p : polys.value().outer()) {
const Point transformed_geom_pt = transformFromMap2Grid(geom_tf_map2grid, p);
cv_polygon.emplace_back(
toCVPoint(transformed_geom_pt, width, height, occupancy_grid.info.resolution));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ void findOcclusionSpots(
bool isCollisionFree(
const grid_map::GridMap & grid, const grid_map::Position & p1, const grid_map::Position & p2,
const double radius);
boost::optional<Polygon2d> generateOccupiedPolygon(
std::optional<Polygon2d> generateOccupiedPolygon(
const Polygon2d & occupancy_poly, const Polygons2d & stuck_vehicle_foot_prints,
const Polygons2d & moving_vehicle_foot_prints, const Point & position);
//!< @brief generate occupied polygon from foot print
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -406,11 +406,11 @@ bool generatePossibleCollisionsFromGridMap(
const auto pc = generateOneNotableCollisionFromOcclusionSpot(
grid, occlusion_spot_positions, offset_from_start_to_ego, base_point, path_lanelet, param,
debug_data);
if (pc == boost::none) continue;
const double lateral_distance = std::abs(pc.get().arc_lane_dist_at_collision.distance);
if (pc) continue;
const double lateral_distance = std::abs(pc.value().arc_lane_dist_at_collision.distance);
if (lateral_distance > distance_lower_bound) continue;
distance_lower_bound = lateral_distance;
possible_collisions.emplace_back(pc.get());
possible_collisions.emplace_back(pc.value());
}
return !possible_collisions.empty();
}
Expand All @@ -423,7 +423,7 @@ bool isBlockedByPartition(const LineString2d & direction, const BasicPolygons2d
return false;
}

boost::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
const grid_map::GridMap & grid, const std::vector<grid_map::Position> & occlusion_spot_positions,
const double offset_from_start_to_ego, const Point2d base_point,
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data)
Expand Down Expand Up @@ -473,7 +473,7 @@ boost::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionS
has_collision = true;
}
if (has_collision) return candidate;
return boost::none;
return std::nullopt;
}

} // namespace occlusion_spot_utils
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,6 @@
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <visualization_msgs/msg/marker.hpp>

#include <boost/optional.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/LaneletMap.h>
#include <tf2/utils.h>
Expand Down Expand Up @@ -67,7 +65,7 @@ using lanelet::ConstLineString2d;
using lanelet::LaneletMapPtr;
using lanelet::geometry::fromArcCoordinates;
using lanelet::geometry::toArcCoordinates;
using DetectionAreaIdx = boost::optional<std::pair<double, double>>;
using DetectionAreaIdx = std::optional<std::pair<double, double>>;
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;

namespace occlusion_spot_utils
Expand Down Expand Up @@ -240,7 +238,7 @@ void calcSlowDownPointsForPossibleCollision(
const int closest_idx, const PathWithLaneId & path, const double offset,
std::vector<PossibleCollisionInfo> & possible_collisions);
//!< @brief convert a set of occlusion spots found on detection_area slice
boost::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpot(
const grid_map::GridMap & grid, const std::vector<grid_map::Position> & occlusion_spot_positions,
const double offset_from_start_to_ego, const Point2d base_point,
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data);
Expand Down

0 comments on commit 389a89c

Please sign in to comment.