Skip to content
This repository has been archived by the owner on Jul 1, 2024. It is now read-only.

Commit

Permalink
remove pointer passing in lanelet2_extension
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Jan 12, 2024
1 parent 8e8b0c7 commit e4e39bd
Show file tree
Hide file tree
Showing 5 changed files with 132 additions and 183 deletions.
42 changes: 19 additions & 23 deletions tmp/lanelet2_extension/include/lanelet2_extension/utility/query.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <lanelet2_routing/RoutingGraph.h>

#include <limits>
#include <optional>
#include <string>
#include <vector>

Expand Down Expand Up @@ -164,13 +165,13 @@ lanelet::ConstLineStrings3d getLinkedParkingSpaces(
const lanelet::ConstLanelet & lanelet, const lanelet::ConstLineStrings3d & all_parking_spaces,
const lanelet::ConstPolygons3d & all_parking_lots);
// query linked lanelets from parking space
bool getLinkedLanelet(
std::optional<lanelet::ConstLanelet> getLinkedLanelet(
const lanelet::ConstLineString3d & parking_space,
const lanelet::ConstLanelets & all_road_lanelets,
const lanelet::ConstPolygons3d & all_parking_lots, lanelet::ConstLanelet * linked_lanelet);
bool getLinkedLanelet(
const lanelet::ConstPolygons3d & all_parking_lots);
std::optional<lanelet::ConstLanelet> getLinkedLanelet(
const lanelet::ConstLineString3d & parking_space,
const lanelet::LaneletMapConstPtr & lanelet_map_ptr, lanelet::ConstLanelet * linked_lanelet);
const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
lanelet::ConstLanelets getLinkedLanelets(
const lanelet::ConstLineString3d & parking_space,
const lanelet::ConstLanelets & all_road_lanelets,
Expand All @@ -180,17 +181,16 @@ lanelet::ConstLanelets getLinkedLanelets(
const lanelet::LaneletMapConstPtr & lanelet_map_ptr);

// get linked parking lot from lanelet
bool getLinkedParkingLot(
const lanelet::ConstLanelet & lanelet, const lanelet::ConstPolygons3d & all_parking_lots,
lanelet::ConstPolygon3d * linked_parking_lot);
std::optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
const lanelet::ConstLanelet & lanelet, const lanelet::ConstPolygons3d & all_parking_lots);
// get linked parking lot from current pose of ego car
bool getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position, const lanelet::ConstPolygons3d & all_parking_lots,
lanelet::ConstPolygon3d * linked_parking_lot);
std::optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position,
const lanelet::ConstPolygons3d & all_parking_lots);
// get linked parking lot from parking space
bool getLinkedParkingLot(
std::optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
const lanelet::ConstLineString3d & parking_space,
const lanelet::ConstPolygons3d & all_parking_lots, lanelet::ConstPolygon3d * linked_parking_lot);
const lanelet::ConstPolygons3d & all_parking_lots);

// query linked parking space from parking lot
lanelet::ConstLineStrings3d getLinkedParkingSpaces(
Expand Down Expand Up @@ -246,23 +246,19 @@ ConstLanelets getAllNeighbors(
const routing::RoutingGraphPtr & graph, const ConstLanelets & road_lanelets,
const geometry_msgs::msg::Point & search_point);

bool getClosestLanelet(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelet * closest_lanelet_ptr);
std::optional<ConstLanelet> getClosestLanelet(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose);

bool getClosestLaneletWithConstrains(
std::optional<ConstLanelet> getClosestLaneletWithConstraints(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelet * closest_lanelet_ptr,
const double dist_threshold = std::numeric_limits<double>::max(),
const double yaw_threshold = std::numeric_limits<double>::max());

bool getCurrentLanelets(
const ConstLanelets & lanelets, const geometry_msgs::msg::Point & search_point,
ConstLanelets * current_lanelets_ptr);
ConstLanelets getCurrentLanelets(
const ConstLanelets & lanelets, const geometry_msgs::msg::Point & search_point);

bool getCurrentLanelets(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelets * current_lanelets_ptr);
ConstLanelets getCurrentLanelets(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose);

/**
* [getSucceedingLaneletSequences retrieves a sequence of lanelets after the given lanelet.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <lanelet2_routing/Forward.h>

#include <map>
#include <optional>

namespace lanelet::utils
{
Expand Down Expand Up @@ -62,11 +63,11 @@ void overwriteLaneletsCenterline(
lanelet::ConstLanelets getConflictingLanelets(
const lanelet::routing::RoutingGraphConstPtr & graph, const lanelet::ConstLanelet & lanelet);

bool lineStringWithWidthToPolygon(
const lanelet::ConstLineString3d & linestring, lanelet::ConstPolygon3d * polygon);
std::optional<lanelet::ConstPolygon3d> lineStringWithWidthToPolygon(
const lanelet::ConstLineString3d & linestring);

bool lineStringToPolygon(
const lanelet::ConstLineString3d & linestring, lanelet::ConstPolygon3d * polygon);
std::optional<lanelet::ConstPolygon3d> lineStringToPolygon(
const lanelet::ConstLineString3d & linestring);

double getLaneletLength2d(const lanelet::ConstLanelet & lanelet);
double getLaneletLength3d(const lanelet::ConstLanelet & lanelet);
Expand Down
Loading

0 comments on commit e4e39bd

Please sign in to comment.