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

Hot fix rrp slow #2526

Merged
merged 3 commits into from
Aug 24, 2021
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 @@ -232,6 +232,7 @@ class RegulatedPurePursuitController : public nav2_core::Controller
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
nav2_costmap_2d::Costmap2D * costmap_;
rclcpp::Logger logger_ {rclcpp::get_logger("RegulatedPurePursuitController")};
rclcpp::Clock::SharedPtr clock_;

double desired_linear_vel_, base_desired_linear_vel_;
double lookahead_dist_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ void RegulatedPurePursuitController::configure(
tf_ = tf;
plugin_name_ = name;
logger_ = node->get_logger();
clock_ = node->get_clock();

double transform_tolerance = 0.1;
double control_frequency = 20.0;
Expand Down Expand Up @@ -436,7 +437,15 @@ bool RegulatedPurePursuitController::isCollisionImminent(
bool RegulatedPurePursuitController::inCollision(const double & x, const double & y)
{
unsigned int mx, my;
costmap_->worldToMap(x, y, mx, my);

if (!costmap_->worldToMap(x, y, mx, my)) {
RCLCPP_WARN_THROTTLE(
logger_, *(clock_), 30000,
"The dimensions of the costmap is too small to successfully check for "
"collisions as far ahead as requested. Proceed at your own risk, slow the robot, or "
"increase your costmap size.");
return false;
}

unsigned char cost = costmap_->getCost(mx, my);

Expand All @@ -450,7 +459,16 @@ bool RegulatedPurePursuitController::inCollision(const double & x, const double
double RegulatedPurePursuitController::costAtPose(const double & x, const double & y)
{
unsigned int mx, my;
costmap_->worldToMap(x, y, mx, my);

if (!costmap_->worldToMap(x, y, mx, my)) {
RCLCPP_FATAL(
logger_,
"The dimensions of the costmap is too small to fully include your robot's footprint, "
"thusly the robot cannot proceed further");
throw nav2_core::PlannerException(
"RegulatedPurePursuitController: Dimensions of the costmap are too small "
"to encapsulate the robot footprint at current speeds!");
}

unsigned char cost = costmap_->getCost(mx, my);
return static_cast<double>(cost);
Expand Down