Skip to content

Commit

Permalink
fix(goal_planner): fix isStopped judgement (#9585)
Browse files Browse the repository at this point in the history
* fix(goal_planner): fix isStopped judgement

Signed-off-by: kosuke55 <[email protected]>

* fix typo

Signed-off-by: kosuke55 <[email protected]>

---------

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 authored Dec 7, 2024
1 parent c9f0f26 commit 90bf2d0
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,8 @@ bool checkOccupancyGridCollision(

bool isStopped(
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> & odometry_buffer,
const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower);
const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower,
const double velocity_upper);

// Flag class for managing whether a certain callback is running in multi-threading
class ScopedFlag
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,8 @@ bool checkOccupancyGridCollision(

bool isStopped(
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> & odometry_buffer,
const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower)
const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower,
const double velocity_upper)
{
odometry_buffer.push_back(self_odometry);
// Delete old data in buffer_stuck_
Expand All @@ -259,7 +260,7 @@ bool isStopped(
bool is_stopped = true;
for (const auto & odometry : odometry_buffer) {
const double ego_vel = utils::l2Norm(odometry->twist.twist.linear);
if (ego_vel > duration_lower) {
if (ego_vel > velocity_upper) {
is_stopped = false;
break;
}
Expand Down Expand Up @@ -879,7 +880,8 @@ bool GoalPlannerModule::canReturnToLaneParking(const PullOverContextData & conte
{
// return only before starting free space parking
if (!isStopped(
odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time)) {
odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time,
parameters_->th_stopped_velocity)) {
return false;
}

Expand Down Expand Up @@ -1760,7 +1762,9 @@ bool GoalPlannerModule::isStuck(
}

constexpr double stuck_time = 5.0;
if (!isStopped(odometry_buffer_stuck_, planner_data->self_odometry, stuck_time)) {
if (!isStopped(
odometry_buffer_stuck_, planner_data->self_odometry, stuck_time,
parameters_->th_stopped_velocity)) {
return false;
}

Expand Down Expand Up @@ -1801,7 +1805,8 @@ bool GoalPlannerModule::hasFinishedCurrentPath(const PullOverContextData & ctx_d
}

if (!isStopped(
odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time)) {
odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time,
parameters_->th_stopped_velocity)) {
return false;
}

Expand Down

0 comments on commit 90bf2d0

Please sign in to comment.