Skip to content

Commit f2f2d46

Browse files
solve issue of sbp not activating
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 765e17f commit f2f2d46

File tree

1 file changed

+0
-28
lines changed

1 file changed

+0
-28
lines changed

planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp

-28
Original file line numberDiff line numberDiff line change
@@ -172,10 +172,7 @@ SamplingPlannerModule::SamplingPlannerModule(
172172

173173
bool SamplingPlannerModule::isExecutionRequested() const
174174
{
175-
const auto & p = planner_data_->parameters;
176175
const auto ego_pose = planner_data_->self_odometry->pose.pose;
177-
const auto goal_pose = planner_data_->route_handler->getGoalPose();
178-
179176
lanelet::ConstLanelet current_lane;
180177

181178
if (!planner_data_->route_handler->getClosestLaneletWithinRoute(ego_pose, &current_lane)) {
@@ -184,31 +181,6 @@ bool SamplingPlannerModule::isExecutionRequested() const
184181
"failed to find closest lanelet within route!!!");
185182
return false;
186183
}
187-
const auto current_lane_sequence = planner_data_->route_handler->getLaneletSequence(
188-
current_lane, ego_pose, p.backward_path_length, p.forward_path_length);
189-
// expand drivable lanes
190-
std::vector<DrivableLanes> drivable_lanes{};
191-
192-
std::for_each(
193-
current_lane_sequence.begin(), current_lane_sequence.end(), [&](const auto & lanelet) {
194-
drivable_lanes.push_back(generateExpandDrivableLanes(lanelet, planner_data_));
195-
});
196-
197-
lanelet::ConstLanelets current_lanes;
198-
199-
for (auto & d : drivable_lanes) {
200-
current_lanes.push_back(d.right_lane);
201-
current_lanes.push_back(d.left_lane);
202-
current_lanes.insert(current_lanes.end(), d.middle_lanes.begin(), d.middle_lanes.end());
203-
}
204-
lanelet::ConstLanelet closest_lanelet_to_ego;
205-
lanelet::utils::query::getClosestLanelet(current_lanes, ego_pose, &closest_lanelet_to_ego);
206-
lanelet::ConstLanelet closest_lanelet_to_goal;
207-
lanelet::utils::query::getClosestLanelet(current_lanes, goal_pose, &closest_lanelet_to_goal);
208-
const bool ego_and_goal_on_same_lanelet =
209-
closest_lanelet_to_goal.id() == closest_lanelet_to_ego.id();
210-
211-
if (!ego_and_goal_on_same_lanelet) return false;
212184

213185
if (getPreviousModuleOutput().reference_path.points.empty()) {
214186
return false;

0 commit comments

Comments
 (0)