Skip to content

Commit 65a9e4f

Browse files
pepisgJoshua Wallace
authored andcommitted
Add allow_unknown parameter to theta star planner (ros-navigation#3286)
* Add allow unknown parameter to theta star planner * Add allow unknown parameter to tests * missing comma * Change cost of unknown tiles * Uncrustify
1 parent 7335d6b commit 65a9e4f

File tree

4 files changed

+21
-3
lines changed

4 files changed

+21
-3
lines changed

nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star.hpp

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,8 @@
2424
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
2525

2626
const double INF_COST = DBL_MAX;
27+
const int UNKNOWN_COST = 255;
28+
const int OBS_COST = 254;
2729
const int LETHAL_COST = 252;
2830

2931
struct coordsM
@@ -70,6 +72,8 @@ class ThetaStar
7072
double w_heuristic_cost_;
7173
/// parameter to set the number of adjacent nodes to be searched on
7274
int how_many_corners_;
75+
/// parameter to set weather the planner can plan through unknown space
76+
bool allow_unknown_;
7377
/// the x-directional and y-directional lengths of the map respectively
7478
int size_x_, size_y_;
7579

@@ -91,7 +95,9 @@ class ThetaStar
9195
*/
9296
inline bool isSafe(const int & cx, const int & cy) const
9397
{
94-
return costmap_->getCost(cx, cy) < LETHAL_COST;
98+
return (costmap_->getCost(
99+
cx,
100+
cy) == UNKNOWN_COST && allow_unknown_) || costmap_->getCost(cx, cy) < LETHAL_COST;
95101
}
96102

97103
/**
@@ -185,7 +191,10 @@ class ThetaStar
185191
bool isSafe(const int & cx, const int & cy, double & cost) const
186192
{
187193
double curr_cost = getCost(cx, cy);
188-
if (curr_cost < LETHAL_COST) {
194+
if ((costmap_->getCost(cx, cy) == UNKNOWN_COST && allow_unknown_) || curr_cost < LETHAL_COST) {
195+
if (costmap_->getCost(cx, cy) == UNKNOWN_COST) {
196+
curr_cost = OBS_COST - 1;
197+
}
189198
cost += w_traversal_cost_ * curr_cost * curr_cost / LETHAL_COST / LETHAL_COST;
190199
return true;
191200
} else {

nav2_theta_star_planner/src/theta_star.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@ ThetaStar::ThetaStar()
2323
w_euc_cost_(2.0),
2424
w_heuristic_cost_(1.0),
2525
how_many_corners_(8),
26+
allow_unknown_(true),
2627
size_x_(0),
2728
size_y_(0),
2829
index_generated_(0)

nav2_theta_star_planner/src/theta_star_planner.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,10 @@ void ThetaStarPlanner::configure(
4545
RCLCPP_WARN(logger_, "Your value for - .how_many_corners was overridden, and is now set to 8");
4646
}
4747

48+
nav2_util::declare_parameter_if_not_declared(
49+
node, name_ + ".allow_unknown", rclcpp::ParameterValue(true));
50+
node->get_parameter(name_ + ".allow_unknown", planner_->allow_unknown_);
51+
4852
nav2_util::declare_parameter_if_not_declared(
4953
node, name_ + ".w_euc_cost", rclcpp::ParameterValue(1.0));
5054
node->get_parameter(name_ + ".w_euc_cost", planner_->w_euc_cost_);
@@ -237,6 +241,8 @@ ThetaStarPlanner::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
237241
} else if (type == ParameterType::PARAMETER_BOOL) {
238242
if (name == name_ + ".use_final_approach_orientation") {
239243
use_final_approach_orientation_ = parameter.as_bool();
244+
} else if (name == name_ + ".allow_unknown") {
245+
planner_->allow_unknown_ = parameter.as_bool();
240246
}
241247
}
242248
}

nav2_theta_star_planner/test/test_theta_star.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -212,7 +212,8 @@ TEST(ThetaStarPlanner, test_theta_star_reconfigure)
212212
{rclcpp::Parameter("test.how_many_corners", 8),
213213
rclcpp::Parameter("test.w_euc_cost", 1.0),
214214
rclcpp::Parameter("test.w_traversal_cost", 2.0),
215-
rclcpp::Parameter("test.use_final_approach_orientation", false)});
215+
rclcpp::Parameter("test.use_final_approach_orientation", false),
216+
rclcpp::Parameter("test.allow_unknown", false)});
216217

217218
rclcpp::spin_until_future_complete(
218219
life_node->get_node_base_interface(),
@@ -224,6 +225,7 @@ TEST(ThetaStarPlanner, test_theta_star_reconfigure)
224225
1.0);
225226
EXPECT_EQ(life_node->get_parameter("test.w_traversal_cost").as_double(), 2.0);
226227
EXPECT_EQ(life_node->get_parameter("test.use_final_approach_orientation").as_bool(), false);
228+
EXPECT_EQ(life_node->get_parameter("test.allow_unknown").as_bool(), false);
227229

228230
rclcpp::spin_until_future_complete(
229231
life_node->get_node_base_interface(),

0 commit comments

Comments
 (0)