20 #include "nav2_costmap_2d/clear_costmap_service.hpp"
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
28 using std::shared_ptr;
30 using ClearExceptRegion = nav2_msgs::srv::ClearCostmapExceptRegion;
31 using ClearAroundRobot = nav2_msgs::srv::ClearCostmapAroundRobot;
32 using ClearEntirely = nav2_msgs::srv::ClearEntireCostmap;
35 const nav2_util::LifecycleNode::WeakPtr & parent,
39 auto node = parent.lock();
40 logger_ = node->get_logger();
43 clear_except_service_ = node->create_service<ClearExceptRegion>(
44 "clear_except_" + costmap_.
getName(),
46 &ClearCostmapService::clearExceptRegionCallback,
this,
47 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
49 clear_around_service_ = node->create_service<ClearAroundRobot>(
50 "clear_around_" + costmap.
getName(),
52 &ClearCostmapService::clearAroundRobotCallback,
this,
53 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
55 clear_entire_service_ = node->create_service<ClearEntirely>(
56 "clear_entirely_" + costmap_.
getName(),
58 &ClearCostmapService::clearEntireCallback,
this,
59 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
65 clear_except_service_.reset();
66 clear_around_service_.reset();
67 clear_entire_service_.reset();
70 void ClearCostmapService::clearExceptRegionCallback(
71 const shared_ptr<rmw_request_id_t>,
72 const shared_ptr<ClearExceptRegion::Request> request,
73 const shared_ptr<ClearExceptRegion::Response>)
77 (
"Received request to clear except a region the " + costmap_.
getName()).c_str());
82 void ClearCostmapService::clearAroundRobotCallback(
83 const shared_ptr<rmw_request_id_t>,
84 const shared_ptr<ClearAroundRobot::Request> request,
85 const shared_ptr<ClearAroundRobot::Response>)
90 void ClearCostmapService::clearEntireCallback(
91 const std::shared_ptr<rmw_request_id_t>,
92 const std::shared_ptr<ClearEntirely::Request>,
93 const std::shared_ptr<ClearEntirely::Response>)
97 (
"Received request to clear entirely the " + costmap_.
getName()).c_str());
106 if (!getPosition(x, y)) {
109 "Cannot clear map because robot pose cannot be retrieved.");
115 for (
auto & layer : *layers) {
116 if (layer->isClearable()) {
117 auto costmap_layer = std::static_pointer_cast<CostmapLayer>(layer);
118 clearLayerRegion(costmap_layer, x, y, reset_distance, invert);
126 void ClearCostmapService::clearLayerRegion(
127 shared_ptr<CostmapLayer> & costmap,
double pose_x,
double pose_y,
double reset_distance,
130 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap->getMutex()));
132 double start_point_x = pose_x - reset_distance / 2;
133 double start_point_y = pose_y - reset_distance / 2;
134 double end_point_x = start_point_x + reset_distance;
135 double end_point_y = start_point_y + reset_distance;
137 int start_x, start_y, end_x, end_y;
138 costmap->worldToMapEnforceBounds(start_point_x, start_point_y, start_x, start_y);
139 costmap->worldToMapEnforceBounds(end_point_x, end_point_y, end_x, end_y);
141 costmap->clearArea(start_x, start_y, end_x, end_y, invert);
143 double ox = costmap->getOriginX(), oy = costmap->getOriginY();
144 double width = costmap->getSizeInMetersX(), height = costmap->getSizeInMetersY();
145 costmap->addExtraBounds(ox, oy, ox + width, oy + height);
150 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_.
getCostmap()->getMutex()));
154 bool ClearCostmapService::getPosition(
double & x,
double & y)
const
156 geometry_msgs::msg::PoseStamped pose;
161 x = pose.pose.position.x;
162 y = pose.pose.position.y;
~ClearCostmapService()
A destructor.
ClearCostmapService()=delete
A constructor.
void clearRegion(double reset_distance, bool invert)
Clears the region outside of a user-specified area reverting to the static map.
void clearEntirely()
Clears all layers.
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...
bool getRobotPose(geometry_msgs::msg::PoseStamped &global_pose)
Get the pose of the robot in the global frame of the costmap.
std::string getName() const
Returns costmap name.
LayeredCostmap * getLayeredCostmap()
Get the layered costmap object used in the node.
void resetLayers()
Reset each individual layer.
Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
unsigned char getDefaultValue()
Get the default background value of the costmap.
std::vector< std::shared_ptr< Layer > > * getPlugins()
Get the vector of pointers to the costmap plugins.