Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(avoidance): prevent endless planning loop in behavior path planner #932

Merged
merged 2 commits into from
Oct 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const AvoidancePlanningData & data, const std::shared_ptr<AvoidanceParameters> & parameters,
DebugData & debug);
const bool is_running, DebugData & debug);
} // namespace behavior_path_planner::utils::avoidance

#endif // BEHAVIOR_PATH_PLANNER__UTILS__AVOIDANCE__UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,10 @@ bool AvoidanceModule::isExecutionRequested() const
return false;
}

return !avoid_data_.target_objects.empty();
return std::any_of(
avoid_data_.target_objects.begin(), avoid_data_.target_objects.end(), [](const auto & o) {
return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
});
}

bool AvoidanceModule::isExecutionReady() const
Expand Down Expand Up @@ -247,12 +250,16 @@ void AvoidanceModule::fillAvoidanceTargetObjects(
using utils::avoidance::filterTargetObjects;
using utils::avoidance::getTargetLanelets;

// Add margin in order to prevent avoidance request chattering only when the module is running.
const auto is_running = getCurrentStatus() == ModuleStatus::RUNNING ||
getCurrentStatus() == ModuleStatus::WAITING_APPROVAL;

// Separate dynamic objects based on whether they are inside or outside of the expanded lanelets.
const auto [object_within_target_lane, object_outside_target_lane] =
utils::avoidance::separateObjectsByPath(
utils::resamplePathWithSpline(
helper_.getPreviousSplineShiftPath().path, parameters_->resample_interval_for_output),
planner_data_, data, parameters_, debug);
planner_data_, data, parameters_, is_running, debug);

for (const auto & object : object_outside_target_lane.objects) {
ObjectData other_object;
Expand Down
31 changes: 30 additions & 1 deletion planning/behavior_path_planner/src/utils/avoidance/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,16 @@

#include <tier4_planning_msgs/msg/avoidance_debug_factor.hpp>

#include <boost/geometry.hpp>
#include <boost/geometry/algorithms/convex_hull.hpp>
#include <boost/geometry/algorithms/correct.hpp>
#include <boost/geometry/algorithms/union.hpp>
#include <boost/geometry/geometries/geometries.hpp>
#include <boost/geometry/geometries/point_xy.hpp>
#include <boost/geometry/strategies/convex_hull.hpp>

#include <lanelet2_routing/RoutingGraphContainer.h>

#include <algorithm>
#include <limits>
#include <memory>
Expand Down Expand Up @@ -1620,7 +1630,7 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const AvoidancePlanningData & data, const std::shared_ptr<AvoidanceParameters> & parameters,
DebugData & debug)
const bool is_running, DebugData & debug)
{
PredictedObjects target_objects;
PredictedObjects other_objects;
Expand Down Expand Up @@ -1657,6 +1667,25 @@ std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
}
}

// expand detection area width only when the module is running.
if (is_running) {
constexpr int PER_CIRCLE = 36;
constexpr double MARGIN = 1.0; // [m]
boost::geometry::strategy::buffer::distance_symmetric<double> distance_strategy(MARGIN);
boost::geometry::strategy::buffer::join_round join_strategy(PER_CIRCLE);
boost::geometry::strategy::buffer::end_round end_strategy(PER_CIRCLE);
boost::geometry::strategy::buffer::point_circle circle_strategy(PER_CIRCLE);
boost::geometry::strategy::buffer::side_straight side_strategy;
boost::geometry::model::multi_polygon<Polygon2d> result;
// Create the buffer of a multi polygon
boost::geometry::buffer(
attention_area, result, distance_strategy, side_strategy, join_strategy, end_strategy,
circle_strategy);
if (!result.empty()) {
attention_area = result.front();
}
}

debug.detection_area = toMsg(attention_area, data.reference_pose.position.z);

const auto objects = planner_data->dynamic_object->objects;
Expand Down
Loading