Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
e481bea
Add plugins Parameter to BT XML for Selective Clearing of Costmap Layers
BCKSELFDRIVEWORLD Sep 23, 2025
520b482
fix typo
BCKSELFDRIVEWORLD Sep 23, 2025
9282d22
remove TODO
BCKSELFDRIVEWORLD Sep 23, 2025
8a82af1
Update nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/c…
BCKSELFDRIVEWORLD Sep 25, 2025
1d24384
Update nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/c…
BCKSELFDRIVEWORLD Sep 25, 2025
ec5eab6
Update nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/c…
BCKSELFDRIVEWORLD Sep 25, 2025
7a5c845
Update nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/c…
BCKSELFDRIVEWORLD Sep 25, 2025
4f0a5fe
Reset master costmap only if a layer was cleared
BCKSELFDRIVEWORLD Sep 25, 2025
b03ad78
fix typo input
BCKSELFDRIVEWORLD Sep 25, 2025
584d698
update nav2_tree_node.xml
BCKSELFDRIVEWORLD Sep 25, 2025
2f46eed
fix
BCKSELFDRIVEWORLD Sep 25, 2025
9528778
added doxygen and mutex and delete updatemap after clearing
BCKSELFDRIVEWORLD Sep 25, 2025
d7f0e28
ClearCostmapService to return success status
BCKSELFDRIVEWORLD Sep 25, 2025
b1391e8
fix typo
BCKSELFDRIVEWORLD Sep 25, 2025
48158c9
Add on_completion methods to ClearCostmap services for handling servi…
BCKSELFDRIVEWORLD Sep 25, 2025
a350359
fix typo
BCKSELFDRIVEWORLD Sep 25, 2025
46284b4
ClearCostmapService to return success status based on all plugins bei…
BCKSELFDRIVEWORLD Sep 29, 2025
a84300e
added log(error)
BCKSELFDRIVEWORLD Sep 29, 2025
65b028a
fix typo
BCKSELFDRIVEWORLD Sep 29, 2025
b31215d
Updated the logic
BCKSELFDRIVEWORLD Sep 29, 2025
8981d97
added logs
BCKSELFDRIVEWORLD Sep 29, 2025
68c3cec
improve logic
BCKSELFDRIVEWORLD Sep 29, 2025
98c5175
fix typo
BCKSELFDRIVEWORLD Sep 29, 2025
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 @@ -16,6 +16,8 @@
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__CLEAR_COSTMAP_SERVICE_HPP_

#include <string>
#include <vector>
#include <memory>

#include "nav2_behavior_tree/bt_service_node.hpp"
#include "nav2_msgs/srv/clear_entire_costmap.hpp"
Expand Down Expand Up @@ -49,6 +51,27 @@ class ClearEntireCostmapService : public BtServiceNode<nav2_msgs::srv::ClearEnti
* @return BT::NodeStatus Status of tick execution
*/
void on_tick() override;

/**
* @brief Check the service response and return appropriate BT status
* @param response Service response containing success status
* @return BT::NodeStatus SUCCESS if service succeeded, FAILURE otherwise
*/
BT::NodeStatus on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearEntireCostmap::Response> response) override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
*/
static BT::PortsList providedPorts()
{
return providedBasicPorts(
{
BT::InputPort<std::vector<std::string>>("plugins",
"List of costmap plugin names to clear. If empty, all plugins will be cleared")
});
}
};

/**
Expand Down Expand Up @@ -76,6 +99,14 @@ class ClearCostmapExceptRegionService
*/
void on_tick() override;

/**
* @brief Check the service response and return appropriate BT status
* @param response Service response containing success status
* @return BT::NodeStatus SUCCESS if service succeeded, FAILURE otherwise
*/
BT::NodeStatus on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearCostmapExceptRegion::Response> response) override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand All @@ -86,7 +117,9 @@ class ClearCostmapExceptRegionService
{
BT::InputPort<double>(
"reset_distance", 1,
"Distance from the robot above which obstacles are cleared")
"Distance from the robot above which obstacles are cleared"),
BT::InputPort<std::vector<std::string>>("plugins",
"List of costmap plugin names to clear. If empty, all plugins will be cleared")
});
}
};
Expand Down Expand Up @@ -115,6 +148,14 @@ class ClearCostmapAroundRobotService : public BtServiceNode<nav2_msgs::srv::Clea
*/
void on_tick() override;

/**
* @brief Check the service response and return appropriate BT status
* @param response Service response containing success status
* @return BT::NodeStatus SUCCESS if service succeeded, FAILURE otherwise
*/
BT::NodeStatus on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearCostmapAroundRobot::Response> response) override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand All @@ -125,7 +166,9 @@ class ClearCostmapAroundRobotService : public BtServiceNode<nav2_msgs::srv::Clea
{
BT::InputPort<double>(
"reset_distance", 1,
"Distance from the robot under which obstacles are cleared")
"Distance from the robot under which obstacles are cleared"),
BT::InputPort<std::vector<std::string>>("plugins",
"List of costmap plugin names to clear. If empty, all plugins will be cleared")
});
}
};
Expand Down Expand Up @@ -154,6 +197,14 @@ class ClearCostmapAroundPoseService : public BtServiceNode<nav2_msgs::srv::Clear
*/
void on_tick() override;

/**
* @brief Check the service response and return appropriate BT status
* @param response Service response containing success status
* @return BT::NodeStatus SUCCESS if service succeeded, FAILURE otherwise
*/
BT::NodeStatus on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearCostmapAroundPose::Response> response) override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand All @@ -166,7 +217,9 @@ class ClearCostmapAroundPoseService : public BtServiceNode<nav2_msgs::srv::Clear
"pose", "Pose around which to clear the costmap"),
BT::InputPort<double>(
"reset_distance", 1.0,
"Distance from the pose under which obstacles are cleared")
"Distance from the pose under which obstacles are cleared"),
BT::InputPort<std::vector<std::string>>("plugins",
"List of costmap plugin names to clear. If empty, all plugins will be cleared")
});
}
};
Expand Down
4 changes: 4 additions & 0 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -67,25 +67,29 @@
<Action ID="ClearEntireCostmap">
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
<input_port name="plugins">List of specific plugins to clear.</input_port>
</Action>

<Action ID="ClearCostmapExceptRegion">
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
<input_port name="reset_distance">Distance from the robot above which obstacles are cleared</input_port>
<input_port name="plugins">List of specific plugins to clear.</input_port>
</Action>

<Action ID="ClearCostmapAroundRobot">
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
<input_port name="reset_distance">Distance from the robot under which obstacles are cleared</input_port>
<input_port name="plugins">List of specific plugins to clear.</input_port>
</Action>

<Action ID="ClearCostmapAroundPose">
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
<input_port name="pose">Pose around which to clear the costmap</input_port>
<input_port name="reset_distance">Distance from the pose under which obstacles are cleared</input_port>
<input_port name="plugins">List of specific plugins to clear.</input_port>
</Action>

<Action ID="ComputePathToPose">
Expand Down
62 changes: 62 additions & 0 deletions nav2_behavior_tree/plugins/action/clear_costmap_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <string>
#include <memory>
#include <vector>

#include "nav2_behavior_tree/plugins/action/clear_costmap_service.hpp"

Expand All @@ -29,9 +30,23 @@ ClearEntireCostmapService::ClearEntireCostmapService(

void ClearEntireCostmapService::on_tick()
{
if (!getInput("plugins", request_->plugins)) {
request_->plugins.clear();
}
increment_recovery_count();
}

BT::NodeStatus ClearEntireCostmapService::on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearEntireCostmap::Response> response)
{
if (response->success) {
return BT::NodeStatus::SUCCESS;
} else {
RCLCPP_ERROR(node_->get_logger(), "ClearEntireCostmap: Failed to clear costmap layers");
return BT::NodeStatus::FAILURE;
}
}

ClearCostmapExceptRegionService::ClearCostmapExceptRegionService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf)
Expand All @@ -42,9 +57,24 @@ ClearCostmapExceptRegionService::ClearCostmapExceptRegionService(
void ClearCostmapExceptRegionService::on_tick()
{
getInput("reset_distance", request_->reset_distance);
if (!getInput("plugins", request_->plugins)) {
request_->plugins.clear();
}

increment_recovery_count();
}

BT::NodeStatus ClearCostmapExceptRegionService::on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearCostmapExceptRegion::Response> response)
{
if (response->success) {
return BT::NodeStatus::SUCCESS;
} else {
RCLCPP_ERROR(node_->get_logger(), "ClearCostmapExceptRegion: Failed to clear costmap layers");
return BT::NodeStatus::FAILURE;
}
}

ClearCostmapAroundRobotService::ClearCostmapAroundRobotService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf)
Expand All @@ -55,9 +85,25 @@ ClearCostmapAroundRobotService::ClearCostmapAroundRobotService(
void ClearCostmapAroundRobotService::on_tick()
{
getInput("reset_distance", request_->reset_distance);

if (!getInput("plugins", request_->plugins)) {
request_->plugins.clear();
}

increment_recovery_count();
}

BT::NodeStatus ClearCostmapAroundRobotService::on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearCostmapAroundRobot::Response> response)
{
if (response->success) {
return BT::NodeStatus::SUCCESS;
} else {
RCLCPP_ERROR(node_->get_logger(), "ClearCostmapAroundRobot: Failed to clear costmap layers");
return BT::NodeStatus::FAILURE;
}
}

ClearCostmapAroundPoseService::ClearCostmapAroundPoseService(
const std::string & service_node_name,
const BT::NodeConfiguration & conf)
Expand All @@ -69,9 +115,25 @@ void ClearCostmapAroundPoseService::on_tick()
{
getInput("pose", request_->pose);
getInput("reset_distance", request_->reset_distance);

if (!getInput("plugins", request_->plugins)) {
request_->plugins.clear();
}

increment_recovery_count();
}

BT::NodeStatus ClearCostmapAroundPoseService::on_completion(
std::shared_ptr<typename nav2_msgs::srv::ClearCostmapAroundPose::Response> response)
{
if (response->success) {
return BT::NodeStatus::SUCCESS;
} else {
RCLCPP_ERROR(node_->get_logger(), "ClearCostmapAroundPose: Failed to clear costmap layers");
return BT::NodeStatus::FAILURE;
}
}

} // namespace nav2_behavior_tree

#include "behaviortree_cpp/bt_factory.h"
Expand Down
22 changes: 17 additions & 5 deletions nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,18 +58,23 @@ class ClearCostmapService

/**
* @brief Clears the region outside of a user-specified area reverting to the static map
* @return true if at least one layer was successfully cleared, false otherwise
*/
void clearRegion(double reset_distance, bool invert);
bool clearRegion(double reset_distance, bool invert, const std::vector<std::string> & plugins);

/**
* @brief Clears the region around a specific pose
* @return true if at least one layer was successfully cleared, false otherwise
*/
void clearAroundPose(const geometry_msgs::msg::PoseStamped & pose, double reset_distance);
bool clearAroundPose(
const geometry_msgs::msg::PoseStamped & pose, double reset_distance,
const std::vector<std::string> & plugins);

/**
* @brief Clears all layers
* @return true if at least one layer was successfully cleared, false otherwise
*/
void clearEntirely();
bool clearEntirely(const std::vector<std::string> & plugins);

private:
// The Logger object for logging
Expand Down Expand Up @@ -126,13 +131,20 @@ class ClearCostmapService
* @brief Function used to clear a given costmap layer
*/
void clearLayerRegion(
std::shared_ptr<CostmapLayer> & costmap, double pose_x, double pose_y, double reset_distance,
bool invert);
std::shared_ptr<CostmapLayer> & costmap,
double pose_x, double pose_y, double reset_distance, bool invert);

/**
* @brief Get the robot's position in the costmap using the master costmap
*/
bool getPosition(double & x, double & y) const;

/**
* @brief Determines whether a specific layer should be cleared based on plugin list and clearable status
*/
bool shouldClearLayer(
const std::shared_ptr<Layer> & layer,
const std::vector<std::string> & plugins) const;
};

} // namespace nav2_costmap_2d
Expand Down
Loading
Loading