39 #include "nav2_costmap_2d/costmap_2d_publisher.hpp"
45 #include "nav2_costmap_2d/cost_values.hpp"
50 char * Costmap2DPublisher::cost_translation_table_ = NULL;
53 const nav2_util::LifecycleNode::WeakPtr & parent,
55 std::string global_frame,
56 std::string topic_name,
57 bool always_send_full_costmap)
59 global_frame_(global_frame),
60 topic_name_(topic_name),
62 always_send_full_costmap_(always_send_full_costmap)
64 auto node = parent.lock();
65 clock_ = node->get_clock();
66 logger_ = node->get_logger();
68 auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
71 costmap_pub_ = node->create_publisher<nav_msgs::msg::OccupancyGrid>(
74 costmap_raw_pub_ = node->create_publisher<nav2_msgs::msg::Costmap>(
77 costmap_update_pub_ = node->create_publisher<map_msgs::msg::OccupancyGridUpdate>(
78 topic_name +
"_updates", custom_qos);
81 costmap_service_ = node->create_service<nav2_msgs::srv::GetCostmap>(
82 "get_costmap", std::bind(
83 &Costmap2DPublisher::costmap_service_callback,
84 this, std::placeholders::_1, std::placeholders::_2,
85 std::placeholders::_3));
87 if (cost_translation_table_ == NULL) {
88 cost_translation_table_ =
new char[256];
91 cost_translation_table_[0] = 0;
92 cost_translation_table_[253] = 99;
93 cost_translation_table_[254] = 100;
94 cost_translation_table_[255] = -1;
98 for (
int i = 1; i < 253; i++) {
99 cost_translation_table_[i] =
static_cast<char>(1 + (97 * (i - 1)) / 251);
119 void Costmap2DPublisher::prepareGrid()
121 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
126 grid_ = std::make_unique<nav_msgs::msg::OccupancyGrid>();
128 grid_->header.frame_id = global_frame_;
129 grid_->header.stamp = clock_->now();
131 grid_->info.resolution = grid_resolution;
133 grid_->info.width = grid_width;
134 grid_->info.height = grid_height;
138 grid_->info.origin.position.x = wx - grid_resolution / 2;
139 grid_->info.origin.position.y = wy - grid_resolution / 2;
140 grid_->info.origin.position.z = 0.0;
141 grid_->info.origin.orientation.w = 1.0;
145 grid_->data.resize(grid_->info.width * grid_->info.height);
147 unsigned char * data = costmap_->
getCharMap();
148 for (
unsigned int i = 0; i < grid_->data.size(); i++) {
149 grid_->data[i] = cost_translation_table_[data[i]];
153 void Costmap2DPublisher::prepareCostmap()
155 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
158 costmap_raw_ = std::make_unique<nav2_msgs::msg::Costmap>();
160 costmap_raw_->header.frame_id = global_frame_;
161 costmap_raw_->header.stamp = clock_->now();
163 costmap_raw_->metadata.layer =
"master";
164 costmap_raw_->metadata.resolution = resolution;
171 costmap_raw_->metadata.origin.position.x = wx - resolution / 2;
172 costmap_raw_->metadata.origin.position.y = wy - resolution / 2;
173 costmap_raw_->metadata.origin.position.z = 0.0;
174 costmap_raw_->metadata.origin.orientation.w = 1.0;
176 costmap_raw_->data.resize(costmap_raw_->metadata.size_x * costmap_raw_->metadata.size_y);
178 unsigned char * data = costmap_->
getCharMap();
179 for (
unsigned int i = 0; i < costmap_raw_->data.size(); i++) {
180 costmap_raw_->data[i] = data[i];
186 if (costmap_raw_pub_->get_subscription_count() > 0) {
188 costmap_raw_pub_->publish(std::move(costmap_raw_));
192 if (always_send_full_costmap_ || grid_resolution != resolution ||
198 if (costmap_pub_->get_subscription_count() > 0) {
200 costmap_pub_->publish(std::move(grid_));
202 }
else if (x0_ < xn_) {
203 if (costmap_update_pub_->get_subscription_count() > 0) {
204 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
206 auto update = std::make_unique<map_msgs::msg::OccupancyGridUpdate>();
207 update->header.stamp = rclcpp::Time();
208 update->header.frame_id = global_frame_;
211 update->width = xn_ - x0_;
212 update->height = yn_ - y0_;
213 update->data.resize(update->width * update->height);
215 for (
unsigned int y = y0_; y < yn_; y++) {
216 for (
unsigned int x = x0_; x < xn_; x++) {
217 unsigned char cost = costmap_->
getCost(x, y);
218 update->data[i++] = cost_translation_table_[cost];
221 costmap_update_pub_->publish(std::move(update));
231 Costmap2DPublisher::costmap_service_callback(
232 const std::shared_ptr<rmw_request_id_t>,
233 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>,
234 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
236 RCLCPP_DEBUG(logger_,
"Received costmap service request");
239 tf2::Quaternion quaternion;
240 quaternion.setRPY(0.0, 0.0, 0.0);
244 auto data_length = size_x * size_y;
245 unsigned char * data = costmap_->
getCharMap();
246 auto current_time = clock_->now();
248 response->map.header.stamp = current_time;
249 response->map.header.frame_id = global_frame_;
250 response->map.metadata.size_x = size_x;
251 response->map.metadata.size_y = size_y;
252 response->map.metadata.resolution = costmap_->
getResolution();
253 response->map.metadata.layer =
"master";
254 response->map.metadata.map_load_time = current_time;
255 response->map.metadata.update_time = current_time;
256 response->map.metadata.origin.position.x = costmap_->
getOriginX();
257 response->map.metadata.origin.position.y = costmap_->
getOriginY();
258 response->map.metadata.origin.position.z = 0.0;
259 response->map.metadata.origin.orientation = tf2::toMsg(quaternion);
260 response->map.data.resize(data_length);
261 response->map.data.assign(data, data + data_length);
~Costmap2DPublisher()
Destructor.
Costmap2DPublisher(const nav2_util::LifecycleNode::WeakPtr &parent, Costmap2D *costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap=false)
Constructor for the Costmap2DPublisher.
void publishCostmap()
Publishes the visualization data over ROS.
A 2D costmap provides a mapping between points in the world and their associated "costs".
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
double getResolution() const
Accessor for the resolution of the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
double getOriginY() const
Accessor for the y origin of the costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
double getOriginX() const
Accessor for the x origin of the costmap.