Skip to content

Commit

Permalink
chore(behavavior_path): refactor use safe return
Browse files Browse the repository at this point in the history
Signed-off-by: tanaka3 <[email protected]>
  • Loading branch information
taikitanaka3 committed Mar 3, 2022
1 parent e6b8840 commit 6d48465
Show file tree
Hide file tree
Showing 5 changed files with 9 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -338,8 +338,9 @@ std::pair<bool, bool> LaneChangeModule::getSafePath(

// select valid path
valid_paths = lane_change_utils::selectValidPaths(
lane_change_paths, current_lanes, check_lanes, route_handler->getOverallGraph(), current_pose,
route_handler->isInGoalRouteSection(current_lanes.back()), route_handler->getGoalPose());
lane_change_paths, current_lanes, check_lanes, *route_handler->getOverallGraphPtr(),
current_pose, route_handler->isInGoalRouteSection(current_lanes.back()),
route_handler->getGoalPose());

if (valid_paths.empty()) {
return std::make_pair(false, false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ std::pair<bool, bool> PullOutModule::getSafePath(

// select valid path
valid_paths = pull_out_utils::selectValidPaths(
pull_out_paths, road_lanes, check_lanes, route_handler->getOverallGraph(), current_pose,
pull_out_paths, road_lanes, check_lanes, *route_handler->getOverallGraphPtr(), current_pose,
route_handler->isInGoalRouteSection(road_lanes.back()), route_handler->getGoalPose());

if (valid_paths.empty()) {
Expand Down Expand Up @@ -493,7 +493,7 @@ std::pair<bool, bool> PullOutModule::getSafeRetreatPath(

// select valid path
valid_paths = pull_out_utils::selectValidPaths(
pull_out_paths, road_lanes, check_lanes, route_handler->getOverallGraph(), current_pose,
pull_out_paths, road_lanes, check_lanes, *route_handler->getOverallGraphPtr(), current_pose,
route_handler->isInGoalRouteSection(road_lanes.back()), route_handler->getGoalPose());

if (valid_paths.empty()) {
Expand Down Expand Up @@ -574,7 +574,7 @@ bool PullOutModule::getBackDistance(

// select valid path
valid_paths = pull_out_utils::selectValidPaths(
pull_out_paths, road_lanes, check_lanes, route_handler->getOverallGraph(), current_pose,
pull_out_paths, road_lanes, check_lanes, *route_handler->getOverallGraphPtr(), current_pose,
route_handler->isInGoalRouteSection(road_lanes.back()), route_handler->getGoalPose());

if (valid_paths.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -353,8 +353,9 @@ std::pair<bool, bool> PullOverModule::getSafePath(

// select valid path
valid_paths = pull_over_utils::selectValidPaths(
pull_over_paths, current_lanes, check_lanes, route_handler->getOverallGraph(), current_pose,
route_handler->isInGoalRouteSection(current_lanes.back()), route_handler->getGoalPose());
pull_over_paths, current_lanes, check_lanes, *route_handler->getOverallGraphPtr(),
current_pose, route_handler->isInGoalRouteSection(current_lanes.back()),
route_handler->getGoalPose());

if (valid_paths.empty()) {
return std::make_pair(false, false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,6 @@ class RouteHandler
bool isMapMsgReady() const;
lanelet::routing::RoutingGraphPtr getRoutingGraphPtr() const;
lanelet::traffic_rules::TrafficRulesPtr getTrafficRulesPtr() const;
lanelet::routing::RoutingGraphContainer getOverallGraph() const;
std::shared_ptr<const lanelet::routing::RoutingGraphContainer> getOverallGraphPtr() const;
lanelet::LaneletMapPtr getLaneletMapPtr() const;

Expand Down
6 changes: 0 additions & 6 deletions planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1283,12 +1283,6 @@ lanelet::traffic_rules::TrafficRulesPtr RouteHandler::getTrafficRulesPtr() const
return traffic_rules_ptr_;
}

// TODO(tanaka): remove this
lanelet::routing::RoutingGraphContainer RouteHandler::getOverallGraph() const
{
return *overall_graphs_ptr_;
}

std::shared_ptr<const lanelet::routing::RoutingGraphContainer> RouteHandler::getOverallGraphPtr()
const
{
Expand Down

0 comments on commit 6d48465

Please sign in to comment.