38 #include <boost/bind.hpp> 
   48                                        std::string topic_name, 
bool always_send_full_costmap) :
 
   49     node(ros_node), costmap_(costmap), global_frame_(global_frame), active_(false),
 
   50     always_send_full_costmap_(always_send_full_costmap)
 
   52   costmap_pub_ = ros_node->
advertise<nav_msgs::OccupancyGrid>(topic_name, 1,
 
   53                                                     boost::bind(&Costmap2DPublisher::onNewSubscription, 
this, _1));
 
   54   costmap_update_pub_ = ros_node->
advertise<map_msgs::OccupancyGridUpdate>(topic_name + 
"_updates", 1);
 
   56   if (cost_translation_table_ == NULL)
 
   58     cost_translation_table_ = 
new char[256];
 
   61     cost_translation_table_[0] = 0;  
 
   62     cost_translation_table_[253] = 99;  
 
   63     cost_translation_table_[254] = 100;  
 
   64     cost_translation_table_[255] = -1;  
 
   68     for (
int i = 1; i < 253; i++)
 
   70       cost_translation_table_[ i ] = char(1 + (97 * (i - 1)) / 251);
 
   75   x0_ = costmap_->getSizeInCellsX();
 
   76   y0_ = costmap_->getSizeInCellsY();
 
   79 Costmap2DPublisher::~Costmap2DPublisher()
 
   90 void Costmap2DPublisher::prepareGrid()
 
   92   boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
 
   93   double resolution = costmap_->getResolution();
 
   95   grid_.header.frame_id = global_frame_;
 
   97   grid_.info.resolution = resolution;
 
   99   grid_.info.width = costmap_->getSizeInCellsX();
 
  100   grid_.info.height = costmap_->getSizeInCellsY();
 
  103   costmap_->mapToWorld(0, 0, wx, wy);
 
  104   grid_.info.origin.position.x = wx - resolution / 2;
 
  105   grid_.info.origin.position.y = wy - resolution / 2;
 
  106   grid_.info.origin.position.z = 0.0;
 
  107   grid_.info.origin.orientation.w = 1.0;
 
  108   saved_origin_x_ = costmap_->getOriginX();
 
  109   saved_origin_y_ = costmap_->getOriginY();
 
  111   grid_.data.resize(grid_.info.width * grid_.info.height);
 
  113   unsigned char* data = costmap_->getCharMap();
 
  114   for (
unsigned int i = 0; i < grid_.data.size(); i++)
 
  116     grid_.data[i] = cost_translation_table_[ data[ i ]];
 
  120 void Costmap2DPublisher::publishCostmap()
 
  122   if (costmap_pub_.getNumSubscribers() == 0)
 
  128   boost::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
 
  129   float resolution = costmap_->getResolution();
 
  131   if (always_send_full_costmap_ || grid_.info.resolution != resolution ||
 
  132       grid_.info.width != costmap_->getSizeInCellsX() ||
 
  133       grid_.info.height != costmap_->getSizeInCellsY() ||
 
  134       saved_origin_x_ != costmap_->getOriginX() ||
 
  135       saved_origin_y_ != costmap_->getOriginY())
 
  138     costmap_pub_.publish(grid_);
 
  143     map_msgs::OccupancyGridUpdate 
update;
 
  145     update.header.frame_id = global_frame_;
 
  149     update.height = yn_ - y0_;
 
  153     for (
unsigned int y = y0_; y < yn_; y++)
 
  155       for (
unsigned int x = x0_; x < xn_; x++)
 
  157         unsigned char cost = costmap_->getCost(x, y);
 
  158         update.data[i++] = cost_translation_table_[ cost ];
 
  161     costmap_update_pub_.publish(update);
 
  165   x0_ = costmap_->getSizeInCellsX();
 
  166   y0_ = costmap_->getSizeInCellsY();