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(goal_planner): fix isStopped judgement #9585

Merged
merged 2 commits into from
Dec 7, 2024
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 @@ -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
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1878 to 1883, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -244,7 +244,8 @@

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 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 @@
{
// 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 @@
}

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 @@
}

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
Loading