Skip to content
Merged
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
16 changes: 14 additions & 2 deletions nav2_theta_star_planner/src/theta_star_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,8 +95,20 @@ nav_msgs::msg::Path ThetaStarPlanner::createPlan(

// Corner case of start and goal beeing on the same cell
unsigned int mx_start, my_start, mx_goal, my_goal;
planner_->costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx_start, my_start);
planner_->costmap_->worldToMap(goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal);
if (!planner_->costmap_->worldToMap(
start.pose.position.x, start.pose.position.y, mx_start, my_start))
{
RCLCPP_WARN(logger_, "Start Coordinates were outside map bounds");
return global_path;
}

if (!planner_->costmap_->worldToMap(
goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal))
{
RCLCPP_WARN(logger_, "Goal Coordinates were outside map bounds");
return global_path;
}

if (mx_start == mx_goal && my_start == my_goal) {
if (planner_->costmap_->getCost(mx_start, my_start) == nav2_costmap_2d::LETHAL_OBSTACLE) {
RCLCPP_WARN(logger_, "Failed to create a unique pose path because of obstacles");
Expand Down