Skip to content

Commit

Permalink
minor imporvement
Browse files Browse the repository at this point in the history
  • Loading branch information
stevedanomodolor committed Mar 25, 2024
1 parent 573250b commit de2716f
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion nav2_smac_planner/src/a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ bool AStarAlgorithm<NodeT>::areInputsValid()
// Check if ending point is valid
if (getToleranceHeuristic() < 0.001) {
// if any goal is valid, then all goals are valid
auto goal = *_goalsSet.begin();
auto goal = *_goalsSet.begin();
if (!goal->isNodeValid(_traverse_unknown, _collision_checker)) {
throw nav2_core::GoalOccupied("Goal was in lethal cost");
}
Expand Down
4 changes: 2 additions & 2 deletions nav2_smac_planner/test/test_a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -351,7 +351,7 @@ TEST(AStarTest, test_se2_single_pose_path)
delete costmapA;
}

TEST(AStarTest, test_goal_heading_goals)
TEST(AStarTest, test_goal_heading_mode)
{
auto lnode = std::make_shared<rclcpp_lifecycle::LifecycleNode>("test");
nav2_smac_planner::SearchInfo info;
Expand All @@ -373,6 +373,7 @@ TEST(AStarTest, test_goal_heading_goals)
double max_planning_time = 120.0;
int num_it = 0;

// BIDIRECTIONAL goal heading mode
a_star.initialize(
false, max_iterations, it_on_approach, terminal_checking_interval,
max_planning_time, 401, size_theta, nav2_smac_planner::GoalHeadingMode::BIDIRECTIONAL);
Expand All @@ -390,7 +391,6 @@ TEST(AStarTest, test_goal_heading_goals)
std::make_unique<nav2_smac_planner::GridCollisionChecker>(costmap_ros, size_theta, lnode);
checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0);

// BIDIRECTIONAL goal heading mode
a_star.setCollisionChecker(checker.get());
a_star.setStart(10u, 10u, 0u);
a_star.setGoal(80u, 80u, 40u);
Expand Down

0 comments on commit de2716f

Please sign in to comment.