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

Add allow_unknown parameter to theta star planner #3286

Merged
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 @@ -24,6 +24,8 @@
#include "nav2_costmap_2d/costmap_2d_ros.hpp"

const double INF_COST = DBL_MAX;
const int UNKNOWN_COST = 255;
const int OBS_COST = 254;
const int LETHAL_COST = 252;

struct coordsM
Expand Down Expand Up @@ -70,6 +72,8 @@ class ThetaStar
double w_heuristic_cost_;
/// parameter to set the number of adjacent nodes to be searched on
int how_many_corners_;
/// parameter to set weather the planner can plan through unknown space
bool allow_unknown_;
/// the x-directional and y-directional lengths of the map respectively
int size_x_, size_y_;

Expand All @@ -91,7 +95,9 @@ class ThetaStar
*/
inline bool isSafe(const int & cx, const int & cy) const
{
return costmap_->getCost(cx, cy) < LETHAL_COST;
return (costmap_->getCost(
cx,
cy) == UNKNOWN_COST && allow_unknown_) || costmap_->getCost(cx, cy) < LETHAL_COST;
}

/**
Expand Down Expand Up @@ -185,7 +191,10 @@ class ThetaStar
bool isSafe(const int & cx, const int & cy, double & cost) const
{
double curr_cost = getCost(cx, cy);
if (curr_cost < LETHAL_COST) {
if ((costmap_->getCost(cx, cy) == UNKNOWN_COST && allow_unknown_) || curr_cost < LETHAL_COST) {
Copy link
Contributor Author

@pepisg pepisg Nov 15, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

not sure if a different cost should be considered for the planning itself when the cell is unknown rather than using the maximum (which if I understand correctly would penalize unknown tiles the same way as obstacles). What do you think @SteveMacenski ?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Look at what NavFn does with this value and you can copy that methodology here

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

just to confirm, that is setting it to the obstacle cost - 1?

if (costmap_->getCost(cx, cy) == UNKNOWN_COST) {
curr_cost = OBS_COST - 1;
}
cost += w_traversal_cost_ * curr_cost * curr_cost / LETHAL_COST / LETHAL_COST;
return true;
} else {
Expand Down
1 change: 1 addition & 0 deletions nav2_theta_star_planner/src/theta_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ ThetaStar::ThetaStar()
w_euc_cost_(2.0),
w_heuristic_cost_(1.0),
how_many_corners_(8),
allow_unknown_(true),
size_x_(0),
size_y_(0),
index_generated_(0)
Expand Down
6 changes: 6 additions & 0 deletions nav2_theta_star_planner/src/theta_star_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,10 @@ void ThetaStarPlanner::configure(
RCLCPP_WARN(logger_, "Your value for - .how_many_corners was overridden, and is now set to 8");
}

nav2_util::declare_parameter_if_not_declared(
node, name_ + ".allow_unknown", rclcpp::ParameterValue(true));
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
node->get_parameter(name_ + ".allow_unknown", planner_->allow_unknown_);

nav2_util::declare_parameter_if_not_declared(
node, name_ + ".w_euc_cost", rclcpp::ParameterValue(1.0));
node->get_parameter(name_ + ".w_euc_cost", planner_->w_euc_cost_);
Expand Down Expand Up @@ -237,6 +241,8 @@ ThetaStarPlanner::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
} else if (type == ParameterType::PARAMETER_BOOL) {
if (name == name_ + ".use_final_approach_orientation") {
use_final_approach_orientation_ = parameter.as_bool();
} else if (name == name_ + ".allow_unknown") {
planner_->allow_unknown_ = parameter.as_bool();
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
}
}
}
Expand Down
4 changes: 3 additions & 1 deletion nav2_theta_star_planner/test/test_theta_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,8 @@ TEST(ThetaStarPlanner, test_theta_star_reconfigure)
{rclcpp::Parameter("test.how_many_corners", 8),
rclcpp::Parameter("test.w_euc_cost", 1.0),
rclcpp::Parameter("test.w_traversal_cost", 2.0),
rclcpp::Parameter("test.use_final_approach_orientation", false)});
rclcpp::Parameter("test.use_final_approach_orientation", false),
rclcpp::Parameter("test.allow_unknown", false)});

rclcpp::spin_until_future_complete(
life_node->get_node_base_interface(),
Expand All @@ -224,6 +225,7 @@ TEST(ThetaStarPlanner, test_theta_star_reconfigure)
1.0);
EXPECT_EQ(life_node->get_parameter("test.w_traversal_cost").as_double(), 2.0);
EXPECT_EQ(life_node->get_parameter("test.use_final_approach_orientation").as_bool(), false);
EXPECT_EQ(life_node->get_parameter("test.allow_unknown").as_bool(), false);

rclcpp::spin_until_future_complete(
life_node->get_node_base_interface(),
Expand Down