ClearCostmapAroundPose Service
Package: nav2_msgs
Category: Costmap Services
Clear costmap within a specified distance around a given pose
Message Definitions
Request Message
Field | Type | Description |
---|---|---|
pose |
geometry_msgs/PoseStamped |
Target pose around which to clear the costmap |
reset_distance |
float64 |
Distance radius in meters within which to clear costmap cells |
Response Message
Field | Type | Description |
---|---|---|
response |
std_msgs/Empty |
Empty response indicating completion |
Usage Examples
Python
import rclpy
from rclpy.node import Node
from nav2_msgs.srv import ClearCostmapAroundPose
from geometry_msgs.msg import PoseStamped, PoseWithCovarianceStamped
class ClearCostmapAroundPoseClient(Node):
def __init__(self):
super().__init__('clearcostmaparoundpose_client')
self.client = self.create_client(ClearCostmapAroundPose, 'global_costmap/clear_around_global_costmap')
def send_request(self):
request = ClearCostmapAroundPose.Request()
request.pose.header.frame_id = 'map'
request.pose.header.stamp = self.get_clock().now().to_msg()
request.pose.pose.position.x = 2.0
request.pose.pose.position.y = 1.0
request.pose.pose.position.z = 0.0
request.pose.pose.orientation.w = 1.0
request.reset_distance = 2.0
self.client.wait_for_service()
future = self.client.call_async(request)
return future
def main():
rclpy.init()
client = ClearCostmapAroundPoseClient()
future = client.send_request()
rclpy.spin_until_future_complete(client, future)
if future.result():
client.get_logger().info('Clear costmap around a specific pose completed')
else:
client.get_logger().error('Failed to clear costmap around a specific pose')
client.destroy_node()
rclpy.shutdown()
C++
#include "rclcpp/rclcpp.hpp"
#include "nav2_msgs/srv/clearcostmaparoundpose.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
class ClearCostmapAroundPoseClient : public rclcpp::Node
{
public:
ClearCostmapAroundPoseClient() : Node("clearcostmaparoundpose_client")
{
client_ = create_client<nav2_msgs::srv::ClearCostmapAroundPose>("global_costmap/clear_around_global_costmap");
}
void send_request()
{
auto request = std::make_shared<nav2_msgs::srv::ClearCostmapAroundPose::Request>();
request->pose.header.frame_id = "map";
request->pose.header.stamp = this->now();
request->pose.pose.position.x = 2.0;
request->pose.pose.position.y = 1.0;
request->pose.pose.position.z = 0.0;
request->pose.pose.orientation.w = 1.0;
request->reset_distance = 2.0;
client_->wait_for_service();
auto result_future = client_->async_send_request(request);
if (rclcpp::spin_until_future_complete(shared_from_this(), result_future) ==
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_INFO(get_logger(), "Clear costmap around a specific pose completed");
}
else
{
RCLCPP_ERROR(get_logger(), "Failed to clear costmap around a specific pose");
}
}
private:
rclcpp::Client<nav2_msgs::srv::ClearCostmapAroundPose>::SharedPtr client_;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto client = std::make_shared<ClearCostmapAroundPoseClient>();
client->send_request();
rclcpp::shutdown();
return 0;
}