Skip to content

Commit 0ffc0fb

Browse files
authored
Improvements in RemoveInCollisionGoals and adjacent features (#4676)
* improvements Signed-off-by: Tony Najjar <[email protected]> * ament_uncrustify Signed-off-by: Tony Najjar <[email protected]> * Fix formatting Signed-off-by: Tony Najjar <[email protected]> * fix building Signed-off-by: Tony Najjar <[email protected]> * fixes Signed-off-by: Tony Najjar <[email protected]> * add stamp Signed-off-by: Tony Najjar <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]>
1 parent 5dd7ad1 commit 0ffc0fb

File tree

7 files changed

+62
-42
lines changed

7 files changed

+62
-42
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -52,17 +52,23 @@ class RemoveInCollisionGoals : public BtServiceNode<nav2_msgs::srv::GetCosts>
5252

5353
static BT::PortsList providedPorts()
5454
{
55-
return providedBasicPorts({
55+
return providedBasicPorts(
56+
{
5657
BT::InputPort<Goals>("input_goals", "Original goals to remove from"),
57-
BT::InputPort<double>("cost_threshold", 254.0,
58+
BT::InputPort<double>(
59+
"cost_threshold", 254.0,
5860
"Cost threshold for considering a goal in collision"),
5961
BT::InputPort<bool>("use_footprint", true, "Whether to use footprint cost"),
62+
BT::InputPort<bool>(
63+
"consider_unknown_as_obstacle", false,
64+
"Whether to consider unknown cost as obstacle"),
6065
BT::OutputPort<Goals>("output_goals", "Goals with in-collision goals removed"),
61-
});
66+
});
6267
}
6368

6469
private:
6570
bool use_footprint_;
71+
bool consider_unknown_as_obstacle_;
6672
double cost_threshold_;
6773
Goals input_goals_;
6874
};

nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ void RemoveInCollisionGoals::on_tick()
3737
getInput("use_footprint", use_footprint_);
3838
getInput("cost_threshold", cost_threshold_);
3939
getInput("input_goals", input_goals_);
40+
getInput("consider_unknown_as_obstacle", consider_unknown_as_obstacle_);
4041

4142
if (input_goals_.empty()) {
4243
setOutput("output_goals", input_goals_);
@@ -47,11 +48,7 @@ void RemoveInCollisionGoals::on_tick()
4748
request_->use_footprint = use_footprint_;
4849

4950
for (const auto & goal : input_goals_) {
50-
geometry_msgs::msg::Pose2D pose;
51-
pose.x = goal.pose.position.x;
52-
pose.y = goal.pose.position.y;
53-
pose.theta = tf2::getYaw(goal.pose.orientation);
54-
request_->poses.push_back(pose);
51+
request_->poses.push_back(goal);
5552
}
5653
}
5754

@@ -60,10 +57,18 @@ BT::NodeStatus RemoveInCollisionGoals::on_completion(
6057
{
6158
Goals valid_goal_poses;
6259
for (size_t i = 0; i < response->costs.size(); ++i) {
63-
if (response->costs[i] < cost_threshold_) {
60+
if ((response->costs[i] == 255 && !consider_unknown_as_obstacle_) ||
61+
response->costs[i] < cost_threshold_)
62+
{
6463
valid_goal_poses.push_back(input_goals_[i]);
6564
}
6665
}
66+
// Inform if all goals have been removed
67+
if (valid_goal_poses.empty()) {
68+
RCLCPP_INFO(
69+
node_->get_logger(),
70+
"All goals are in collision and have been removed from the list");
71+
}
6772
setOutput("output_goals", valid_goal_poses);
6873
return BT::NodeStatus::SUCCESS;
6974
}

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 16 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,8 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
254254
// Service to get the cost at a point
255255
get_cost_service_ = create_service<nav2_msgs::srv::GetCosts>(
256256
"get_cost_" + getName(),
257-
std::bind(&Costmap2DROS::getCostsCallback, this, std::placeholders::_1, std::placeholders::_2,
257+
std::bind(
258+
&Costmap2DROS::getCostsCallback, this, std::placeholders::_1, std::placeholders::_2,
258259
std::placeholders::_3));
259260

260261
// Add cleaning service
@@ -835,26 +836,35 @@ void Costmap2DROS::getCostsCallback(
835836
Costmap2D * costmap = layered_costmap_->getCostmap();
836837

837838
for (const auto & pose : request->poses) {
838-
bool in_bounds = costmap->worldToMap(pose.x, pose.y, mx, my);
839+
geometry_msgs::msg::PoseStamped pose_transformed;
840+
transformPoseToGlobalFrame(pose, pose_transformed);
841+
bool in_bounds = costmap->worldToMap(
842+
pose_transformed.pose.position.x,
843+
pose_transformed.pose.position.y, mx, my);
839844

840845
if (!in_bounds) {
841-
response->costs.push_back(-1.0);
846+
response->costs.push_back(NO_INFORMATION);
842847
continue;
843848
}
849+
double yaw = tf2::getYaw(pose_transformed.pose.orientation);
844850

845851
if (request->use_footprint) {
846852
Footprint footprint = layered_costmap_->getFootprint();
847853
FootprintCollisionChecker<Costmap2D *> collision_checker(costmap);
848854

849855
RCLCPP_DEBUG(
850856
get_logger(), "Received request to get cost at footprint pose (%.2f, %.2f, %.2f)",
851-
pose.x, pose.y, pose.theta);
857+
pose_transformed.pose.position.x, pose_transformed.pose.position.y, yaw);
852858

853859
response->costs.push_back(
854-
collision_checker.footprintCostAtPose(pose.x, pose.y, pose.theta, footprint));
860+
collision_checker.footprintCostAtPose(
861+
pose_transformed.pose.position.x,
862+
pose_transformed.pose.position.y, yaw, footprint));
855863
} else {
856864
RCLCPP_DEBUG(
857-
get_logger(), "Received request to get cost at point (%f, %f)", pose.x, pose.y);
865+
get_logger(), "Received request to get cost at point (%f, %f)",
866+
pose_transformed.pose.position.x,
867+
pose_transformed.pose.position.y);
858868

859869
// Get the cost at the map coordinates
860870
response->costs.push_back(static_cast<float>(costmap->getCost(mx, my)));

nav2_costmap_2d/src/layered_costmap.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -72,11 +72,11 @@ LayeredCostmap::LayeredCostmap(std::string global_frame, bool rolling_window, bo
7272
footprint_(std::make_shared<std::vector<geometry_msgs::msg::Point>>())
7373
{
7474
if (track_unknown) {
75-
primary_costmap_.setDefaultValue(255);
76-
combined_costmap_.setDefaultValue(255);
75+
primary_costmap_.setDefaultValue(NO_INFORMATION);
76+
combined_costmap_.setDefaultValue(NO_INFORMATION);
7777
} else {
78-
primary_costmap_.setDefaultValue(0);
79-
combined_costmap_.setDefaultValue(0);
78+
primary_costmap_.setDefaultValue(FREE_SPACE);
79+
combined_costmap_.setDefaultValue(FREE_SPACE);
8080
}
8181
}
8282

nav2_costmap_2d/test/unit/costmap_cost_service_test.cpp

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -50,9 +50,9 @@ class GetCostServiceTest : public ::testing::Test
5050
TEST_F(GetCostServiceTest, TestWithoutFootprint)
5151
{
5252
auto request = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
53-
geometry_msgs::msg::Pose2D pose;
54-
pose.x = 0.5;
55-
pose.y = 1.0;
53+
geometry_msgs::msg::PoseStamped pose;
54+
pose.pose.position.x = 0.5;
55+
pose.pose.position.y = 1.0;
5656
request->poses.push_back(pose);
5757
request->use_footprint = false;
5858

@@ -72,10 +72,12 @@ TEST_F(GetCostServiceTest, TestWithoutFootprint)
7272
TEST_F(GetCostServiceTest, TestWithFootprint)
7373
{
7474
auto request = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
75-
geometry_msgs::msg::Pose2D pose;
76-
pose.x = 0.5;
77-
pose.y = 1.0;
78-
pose.theta = 0.5;
75+
geometry_msgs::msg::PoseStamped pose;
76+
pose.pose.position.x = 0.5;
77+
pose.pose.position.y = 1.0;
78+
tf2::Quaternion q;
79+
q.setRPY(0, 0, 0.5);
80+
pose.pose.orientation = tf2::toMsg(q);
7981
request->poses.push_back(pose);
8082
request->use_footprint = true;
8183

nav2_msgs/srv/GetCosts.srv

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# Get costmap costs at given poses
22

33
bool use_footprint
4-
geometry_msgs/Pose2D[] poses
4+
geometry_msgs/PoseStamped[] poses
55
---
66
float32[] costs

nav2_rviz_plugins/src/costmap_cost_tool.cpp

Lines changed: 12 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -94,23 +94,28 @@ int CostmapCostTool::processMouseEvent(rviz_common::ViewportMouseEvent & event)
9494

9595
void CostmapCostTool::callCostService(float x, float y)
9696
{
97+
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
9798
// Create request for local costmap
9899
auto request = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
99-
geometry_msgs::msg::Pose2D pose;
100-
pose.x = x;
101-
pose.y = y;
100+
geometry_msgs::msg::PoseStamped pose;
101+
pose.header.frame_id = context_->getFixedFrame().toStdString();
102+
pose.header.stamp = node->now();
103+
pose.pose.position.x = x;
104+
pose.pose.position.y = y;
102105
request->poses.push_back(pose);
103106
request->use_footprint = false;
104107

105108
// Call local costmap service
106109
if (local_cost_client_->wait_for_service(std::chrono::seconds(1))) {
107-
local_cost_client_->async_send_request(request,
110+
local_cost_client_->async_send_request(
111+
request,
108112
std::bind(&CostmapCostTool::handleLocalCostResponse, this, std::placeholders::_1));
109113
}
110114

111115
// Call global costmap service
112116
if (global_cost_client_->wait_for_service(std::chrono::seconds(1))) {
113-
global_cost_client_->async_send_request(request,
117+
global_cost_client_->async_send_request(
118+
request,
114119
std::bind(&CostmapCostTool::handleGlobalCostResponse, this, std::placeholders::_1));
115120
}
116121
}
@@ -120,23 +125,15 @@ void CostmapCostTool::handleLocalCostResponse(
120125
{
121126
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
122127
auto response = future.get();
123-
if (response->costs[0] != -1) {
124-
RCLCPP_INFO(node->get_logger(), "Local costmap cost: %.1f", response->costs[0]);
125-
} else {
126-
RCLCPP_ERROR(node->get_logger(), "Failed to get local costmap cost");
127-
}
128+
RCLCPP_INFO(node->get_logger(), "Local costmap cost: %.1f", response->costs[0]);
128129
}
129130

130131
void CostmapCostTool::handleGlobalCostResponse(
131132
rclcpp::Client<nav2_msgs::srv::GetCosts>::SharedFuture future)
132133
{
133134
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
134135
auto response = future.get();
135-
if (response->costs[0] != -1) {
136-
RCLCPP_INFO(node->get_logger(), "Global costmap cost: %.1f", response->costs[0]);
137-
} else {
138-
RCLCPP_ERROR(node->get_logger(), "Failed to get global costmap cost");
139-
}
136+
RCLCPP_INFO(node->get_logger(), "Global costmap cost: %.1f", response->costs[0]);
140137
}
141138
} // namespace nav2_rviz_plugins
142139

0 commit comments

Comments
 (0)