Skip to content

Commit 1b23f84

Browse files
authored
fix(obstacle_avoidance_planner): fix inf loop in mpt (autowarefoundation#1881)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 1279296 commit 1b23f84

File tree

1 file changed

+13
-0
lines changed
  • planning/obstacle_avoidance_planner/src

1 file changed

+13
-0
lines changed

planning/obstacle_avoidance_planner/src/node.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -1141,6 +1141,19 @@ Trajectories ObstacleAvoidancePlanner::optimizeTrajectory(
11411141
return getPrevTrajs(p.path.points);
11421142
}
11431143

1144+
// NOTE: Elastic band sometimes diverges with status = "OSQP_SOLVED".
1145+
constexpr double max_path_change_diff = 1.0e4;
1146+
for (size_t i = 0; i < eb_traj->size(); ++i) {
1147+
const auto & eb_pos = eb_traj->at(i).pose.position;
1148+
const auto & path_pos = path.points.at(std::min(i, path.points.size() - 1)).pose.position;
1149+
1150+
const double diff_x = eb_pos.x - path_pos.x;
1151+
const double diff_y = eb_pos.y - path_pos.y;
1152+
if (max_path_change_diff < std::abs(diff_x) || max_path_change_diff < std::abs(diff_y)) {
1153+
return getPrevTrajs(path.points);
1154+
}
1155+
}
1156+
11441157
// EB has to be solved twice before solving MPT with fixed points
11451158
// since the result of EB is likely to change with/without fixing (1st/2nd EB)
11461159
// that makes MPT fixing points worse.

0 commit comments

Comments
 (0)