Skip to content

Commit a358cd2

Browse files
saka1-ssatoshi-ota
andauthored
fix(staatic_obstacle_avoidance): allow return shift approval even if … (#1324)
fix(staatic_obstacle_avoidance): allow return shift approval even if return shift path is not within drivable area Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> Co-authored-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 4c71844 commit a358cd2

File tree

1 file changed

+31
-18
lines changed
  • planning/behavior_path_avoidance_module/src

1 file changed

+31
-18
lines changed

planning/behavior_path_avoidance_module/src/scene.cpp

+31-18
Original file line numberDiff line numberDiff line change
@@ -1257,32 +1257,45 @@ bool AvoidanceModule::isValidShiftLine(
12571257
}
12581258
}
12591259

1260+
const auto is_return_shift =
1261+
[](const double start_shift_length, const double end_shift_length, const double threshold) {
1262+
return std::abs(start_shift_length) > threshold && std::abs(end_shift_length) < threshold;
1263+
};
1264+
12601265
// check if the vehicle is in road. (yaw angle is not considered)
12611266
{
12621267
const auto minimum_distance = 0.5 * planner_data_->parameters.vehicle_width +
12631268
parameters_->hard_road_shoulder_margin -
12641269
parameters_->max_deviation_from_lane;
12651270

1266-
const size_t start_idx = shift_lines.front().start_idx;
1267-
const size_t end_idx = shift_lines.back().end_idx;
1271+
for (const auto & shift_line : shift_lines) {
1272+
const size_t start_idx = shift_line.start_idx;
1273+
const size_t end_idx = shift_line.end_idx;
12681274

1269-
const auto path = shifter_for_validate.getReferencePath();
1270-
const auto left_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.left_bound));
1271-
const auto right_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.right_bound));
1272-
for (size_t i = start_idx; i <= end_idx; ++i) {
1273-
const auto p = getPoint(path.points.at(i));
1274-
lanelet::BasicPoint2d basic_point{p.x, p.y};
1275-
1276-
const auto shift_length = proposed_shift_path.shift_length.at(i);
1277-
const auto THRESHOLD = minimum_distance + std::abs(shift_length);
1275+
if (is_return_shift(
1276+
shift_line.start_shift_length, shift_line.end_shift_length,
1277+
parameters_->lateral_small_shift_threshold)) {
1278+
continue;
1279+
}
12781280

1279-
if (
1280-
boost::geometry::distance(basic_point, (shift_length > 0.0 ? left_bound : right_bound)) <
1281-
THRESHOLD) {
1282-
RCLCPP_DEBUG_THROTTLE(
1283-
getLogger(), *clock_, 1000,
1284-
"following latest new shift line may cause deviation from drivable area.");
1285-
return false;
1281+
const auto path = shifter_for_validate.getReferencePath();
1282+
const auto left_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.left_bound));
1283+
const auto right_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.right_bound));
1284+
for (size_t i = start_idx; i <= end_idx; ++i) {
1285+
const auto p = getPoint(path.points.at(i));
1286+
lanelet::BasicPoint2d basic_point{p.x, p.y};
1287+
1288+
const auto shift_length = proposed_shift_path.shift_length.at(i);
1289+
const auto THRESHOLD = minimum_distance + std::abs(shift_length);
1290+
1291+
if (
1292+
boost::geometry::distance(basic_point, (shift_length > 0.0 ? left_bound : right_bound)) <
1293+
THRESHOLD) {
1294+
RCLCPP_DEBUG_THROTTLE(
1295+
getLogger(), *clock_, 1000,
1296+
"following latest new shift line may cause deviation from drivable area.");
1297+
return false;
1298+
}
12861299
}
12871300
}
12881301
}

0 commit comments

Comments
 (0)