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,
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();
70 auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
73 costmap_pub_ = node->create_publisher<nav_msgs::msg::OccupancyGrid>(
76 costmap_raw_pub_ = node->create_publisher<nav2_msgs::msg::Costmap>(
79 costmap_update_pub_ = node->create_publisher<map_msgs::msg::OccupancyGridUpdate>(
80 topic_name +
"_updates", custom_qos);
81 costmap_raw_update_pub_ = node->create_publisher<nav2_msgs::msg::CostmapUpdate>(
82 topic_name +
"_raw_updates", custom_qos);
86 std::shared_ptr<rclcpp_lifecycle::LifecycleNode>>>(
87 std::string(
"get_") + topic_name,
90 &Costmap2DPublisher::costmap_service_callback,
this,
91 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
93 if (cost_translation_table_ == NULL) {
94 cost_translation_table_ =
new char[256];
97 cost_translation_table_[0] = 0;
98 cost_translation_table_[253] = 99;
99 cost_translation_table_[254] = 100;
100 cost_translation_table_[255] = -1;
104 for (
int i = 1; i < 253; i++) {
105 cost_translation_table_[i] =
static_cast<char>(1 + (97 * (i - 1)) / 251);
125 void Costmap2DPublisher::updateGridParams()
135 void Costmap2DPublisher::prepareGrid()
137 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
139 grid_ = std::make_unique<nav_msgs::msg::OccupancyGrid>();
141 grid_->header.frame_id = global_frame_;
142 grid_->header.stamp = clock_->now();
144 grid_->info.resolution = grid_resolution_;
146 grid_->info.width = grid_width_;
147 grid_->info.height = grid_height_;
151 grid_->info.origin.position.x = wx - grid_resolution_ / 2;
152 grid_->info.origin.position.y = wy - grid_resolution_ / 2;
153 grid_->info.origin.position.z = map_vis_z_;
154 grid_->info.origin.orientation.w = 1.0;
156 grid_->data.resize(grid_->info.width * grid_->info.height);
158 unsigned char * data = costmap_->
getCharMap();
159 std::transform(data, data + grid_->data.size(), grid_->data.begin(),
160 [](
unsigned char c) {return cost_translation_table_[c];});
163 void Costmap2DPublisher::prepareCostmap()
165 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
168 costmap_raw_ = std::make_unique<nav2_msgs::msg::Costmap>();
170 costmap_raw_->header.frame_id = global_frame_;
171 costmap_raw_->header.stamp = clock_->now();
173 costmap_raw_->metadata.layer =
"master";
174 costmap_raw_->metadata.resolution = resolution;
181 costmap_raw_->metadata.origin.position.x = wx - resolution / 2;
182 costmap_raw_->metadata.origin.position.y = wy - resolution / 2;
183 costmap_raw_->metadata.origin.position.z = 0.0;
184 costmap_raw_->metadata.origin.orientation.w = 1.0;
186 costmap_raw_->data.resize(costmap_raw_->metadata.size_x * costmap_raw_->metadata.size_y);
188 unsigned char * data = costmap_->
getCharMap();
189 memcpy(costmap_raw_->data.data(), data, costmap_raw_->data.size());
192 std::unique_ptr<map_msgs::msg::OccupancyGridUpdate> Costmap2DPublisher::createGridUpdateMsg()
194 auto update = std::make_unique<map_msgs::msg::OccupancyGridUpdate>();
196 update->header.stamp = clock_->now();
197 update->header.frame_id = global_frame_;
200 update->width = xn_ - x0_;
201 update->height = yn_ - y0_;
202 update->data.resize(update->width * update->height);
204 unsigned char * costmap_data = costmap_->
getCharMap();
206 for (std::uint32_t y = y0_; y < yn_; y++) {
207 std::uint32_t row_start = y * map_width + x0_;
208 std::transform(costmap_data + row_start, costmap_data + row_start + update->width,
209 update->data.begin() + i,
210 [](
unsigned char c) {return cost_translation_table_[c];});
216 std::unique_ptr<nav2_msgs::msg::CostmapUpdate> Costmap2DPublisher::createCostmapUpdateMsg()
218 auto msg = std::make_unique<nav2_msgs::msg::CostmapUpdate>();
220 msg->header.stamp = clock_->now();
221 msg->header.frame_id = global_frame_;
224 msg->size_x = xn_ - x0_;
225 msg->size_y = yn_ - y0_;
226 msg->data.resize(msg->size_x * msg->size_y);
228 unsigned char * costmap_data = costmap_->
getCharMap();
231 for (std::uint32_t y = y0_; y < yn_; y++) {
232 std::uint32_t row_start = y * map_width + x0_;
233 std::copy_n(costmap_data + row_start, msg->size_x, msg->data.begin() + i);
242 if (always_send_full_costmap_ || grid_resolution_ != resolution ||
249 if (costmap_pub_->get_subscription_count() > 0) {
251 costmap_pub_->publish(std::move(grid_));
253 if (costmap_raw_pub_->get_subscription_count() > 0) {
255 costmap_raw_pub_->publish(std::move(costmap_raw_));
257 }
else if (x0_ < xn_) {
259 std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
260 if (costmap_update_pub_->get_subscription_count() > 0) {
261 costmap_update_pub_->publish(createGridUpdateMsg());
263 if (costmap_raw_update_pub_->get_subscription_count() > 0) {
264 costmap_raw_update_pub_->publish(createCostmapUpdateMsg());
274 Costmap2DPublisher::costmap_service_callback(
275 const std::shared_ptr<rmw_request_id_t>,
276 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>,
277 const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response)
279 RCLCPP_DEBUG(logger_,
"Received costmap service request");
282 tf2::Quaternion quaternion;
283 quaternion.setRPY(0.0, 0.0, 0.0);
287 auto data_length = size_x * size_y;
288 unsigned char * data = costmap_->
getCharMap();
289 auto current_time = clock_->now();
291 response->map.header.stamp = current_time;
292 response->map.header.frame_id = global_frame_;
293 response->map.metadata.size_x = size_x;
294 response->map.metadata.size_y = size_y;
295 response->map.metadata.resolution = costmap_->
getResolution();
296 response->map.metadata.layer =
"master";
297 response->map.metadata.map_load_time = current_time;
298 response->map.metadata.update_time = current_time;
299 response->map.metadata.origin.position.x = costmap_->
getOriginX();
300 response->map.metadata.origin.position.y = costmap_->
getOriginY();
301 response->map.metadata.origin.position.z = 0.0;
302 response->map.metadata.origin.orientation = tf2::toMsg(quaternion);
303 response->map.data.resize(data_length);
304 response->map.data.assign(data, data + data_length);
~Costmap2DPublisher()
Destructor.
void publishCostmap()
Publishes the visualization data over ROS.
Costmap2DPublisher(const nav2_util::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.
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.
A simple wrapper on ROS2 services server.