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::LifecycleNode::WeakPtr & parent,
55 std::string global_frame,
56 std::string topic_name,
57 bool always_send_full_costmap,
60 global_frame_(global_frame),
61 topic_name_(topic_name),
63 always_send_full_costmap_(always_send_full_costmap),
66 auto node = parent.lock();
67 clock_ = node->get_clock();
68 logger_ = node->get_logger();
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>(
79 costmap_raw_update_pub_ = node->create_publisher<nav2_msgs::msg::CostmapUpdate>(
83 costmap_service_ = node->create_service<nav2_msgs::srv::GetCostmap>(
84 std::string(
"get_") + topic_name,
86 &Costmap2DPublisher::costmap_service_callback,
this,
87 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
89 if (cost_translation_table_ == NULL) {
90 cost_translation_table_ =
new char[256];
93 cost_translation_table_[0] = 0;
94 cost_translation_table_[253] = 99;
95 cost_translation_table_[254] = 100;
96 cost_translation_table_[255] = -1;
100 for (
int i = 1; i < 253; i++) {
101 cost_translation_table_[i] =
static_cast<char>(1 + (97 * (i - 1)) / 251);
121 void Costmap2DPublisher::updateGridParams()
131 void Costmap2DPublisher::prepareGrid()
133 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
135 grid_ = std::make_unique<nav_msgs::msg::OccupancyGrid>();
137 grid_->header.frame_id = global_frame_;
138 grid_->header.stamp = clock_->now();
140 grid_->info.resolution = grid_resolution_;
142 grid_->info.width = grid_width_;
143 grid_->info.height = grid_height_;
147 grid_->info.origin.position.x = wx - grid_resolution_ / 2;
148 grid_->info.origin.position.y = wy - grid_resolution_ / 2;
149 grid_->info.origin.position.z = map_vis_z_;
150 grid_->info.origin.orientation.w = 1.0;
152 grid_->data.resize(grid_->info.width * grid_->info.height);
154 unsigned char * data = costmap_->
getCharMap();
155 std::transform(data, data + grid_->data.size(), grid_->data.begin(),
156 [](
unsigned char c) {return cost_translation_table_[c];});
159 void Costmap2DPublisher::prepareCostmap()
161 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
164 costmap_raw_ = std::make_unique<nav2_msgs::msg::Costmap>();
166 costmap_raw_->header.frame_id = global_frame_;
167 costmap_raw_->header.stamp = clock_->now();
169 costmap_raw_->metadata.layer =
"master";
170 costmap_raw_->metadata.resolution = resolution;
177 costmap_raw_->metadata.origin.position.x = wx - resolution / 2;
178 costmap_raw_->metadata.origin.position.y = wy - resolution / 2;
179 costmap_raw_->metadata.origin.position.z = 0.0;
180 costmap_raw_->metadata.origin.orientation.w = 1.0;
182 costmap_raw_->data.resize(costmap_raw_->metadata.size_x * costmap_raw_->metadata.size_y);
184 unsigned char * data = costmap_->
getCharMap();
185 memcpy(costmap_raw_->data.data(), data, costmap_raw_->data.size());
188 std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> Costmap2DPublisher::createGridUpdateMsg()
190 auto update = std::make_unique<map_msgs::msg::OccupancyGridUpdate>();
192 update->header.stamp = clock_->now();
193 update->header.frame_id = global_frame_;
196 update->width = xn_ - x0_;
197 update->height = yn_ - y0_;
198 update->data.resize(update->width * update->height);
200 unsigned char * costmap_data = costmap_->
getCharMap();
202 for (std::uint32_t y = y0_; y < yn_; y++) {
203 std::uint32_t row_start = y * map_width + x0_;
204 std::transform(costmap_data + row_start, costmap_data + row_start + update->width,
205 update->data.begin() + i,
206 [](
unsigned char c) {return cost_translation_table_[c];});
212 std::unique_ptr<nav2_msgs::msg::CostmapUpdate> Costmap2DPublisher::createCostmapUpdateMsg()
214 auto msg = std::make_unique<nav2_msgs::msg::CostmapUpdate>();
216 msg->header.stamp = clock_->now();
217 msg->header.frame_id = global_frame_;
220 msg->size_x = xn_ - x0_;
221 msg->size_y = yn_ - y0_;
222 msg->data.resize(msg->size_x * msg->size_y);
224 unsigned char * costmap_data = costmap_->
getCharMap();
227 for (std::uint32_t y = y0_; y < yn_; y++) {
228 std::uint32_t row_start = y * map_width + x0_;
229 std::copy_n(costmap_data + row_start, msg->size_x, msg->data.begin() + i);
238 if (always_send_full_costmap_ || grid_resolution_ != resolution ||
245 if (costmap_pub_->get_subscription_count() > 0) {
247 costmap_pub_->publish(std::move(grid_));
249 if (costmap_raw_pub_->get_subscription_count() > 0) {
251 costmap_raw_pub_->publish(std::move(costmap_raw_));
253 }
else if (x0_ < xn_) {
255 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
256 if (costmap_update_pub_->get_subscription_count() > 0) {
257 costmap_update_pub_->publish(createGridUpdateMsg());
259 if (costmap_raw_update_pub_->get_subscription_count() > 0) {
260 costmap_raw_update_pub_->publish(createCostmapUpdateMsg());
270 Costmap2DPublisher::costmap_service_callback(
271 const std::shared_ptr<rmw_request_id_t>,
272 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>,
273 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
275 RCLCPP_DEBUG(logger_,
"Received costmap service request");
278 tf2::Quaternion quaternion;
279 quaternion.setRPY(0.0, 0.0, 0.0);
283 auto data_length = size_x * size_y;
284 unsigned char * data = costmap_->
getCharMap();
285 auto current_time = clock_->now();
287 response->map.header.stamp = current_time;
288 response->map.header.frame_id = global_frame_;
289 response->map.metadata.size_x = size_x;
290 response->map.metadata.size_y = size_y;
291 response->map.metadata.resolution = costmap_->
getResolution();
292 response->map.metadata.layer =
"master";
293 response->map.metadata.map_load_time = current_time;
294 response->map.metadata.update_time = current_time;
295 response->map.metadata.origin.position.x = costmap_->
getOriginX();
296 response->map.metadata.origin.position.y = costmap_->
getOriginY();
297 response->map.metadata.origin.position.z = 0.0;
298 response->map.metadata.origin.orientation = tf2::toMsg(quaternion);
299 response->map.data.resize(data_length);
300 response->map.data.assign(data, data + data_length);
A QoS profile for latched, reliable topics with a history of 1 messages.
~Costmap2DPublisher()
Destructor.
Costmap2DPublisher(const nav2::LifecycleNode::WeakPtr &parent, Costmap2D *costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap=false, double map_vis_z=0.0)
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 * 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.