Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #include <boost/bind.hpp>
00039 #include <costmap_2d/costmap_2d_publisher.h>
00040 #include <costmap_2d/cost_values.h>
00041 
00042 namespace costmap_2d
00043 {
00044 
00045 char* Costmap2DPublisher::cost_translation_table_ = NULL;
00046 
00047 Costmap2DPublisher::Costmap2DPublisher(ros::NodeHandle * ros_node, Costmap2D* costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap) :
00048     node(ros_node), costmap_(costmap), global_frame_(global_frame), active_(false), always_send_full_costmap_(always_send_full_costmap)
00049 {
00050   costmap_pub_ = ros_node->advertise<nav_msgs::OccupancyGrid>( topic_name, 1, boost::bind( &Costmap2DPublisher::onNewSubscription, this, _1 ));
00051   costmap_update_pub_ = ros_node->advertise<map_msgs::OccupancyGridUpdate>( topic_name + "_updates", 1 );
00052 
00053   if( cost_translation_table_ == NULL )
00054   {
00055     cost_translation_table_ = new char[256];
00056 
00057     
00058     cost_translation_table_[0] = 0; 
00059     cost_translation_table_[253] = 99; 
00060     cost_translation_table_[254] = 100; 
00061     cost_translation_table_[255] = -1; 
00062 
00063     
00064     
00065     for( int i = 1; i < 253; i++ )
00066     {
00067       cost_translation_table_[ i ] = char( 1 + (97 * ( i - 1 )) / 251 );
00068     }
00069   }
00070 }
00071 
00072 Costmap2DPublisher::~Costmap2DPublisher()
00073 {
00074 }
00075 
00076 void Costmap2DPublisher::onNewSubscription( const ros::SingleSubscriberPublisher& pub )
00077 {
00078   prepareGrid();
00079   pub.publish( grid_ );
00080 }
00081 
00082 
00083 void Costmap2DPublisher::prepareGrid()
00084 {
00085   boost::shared_lock < boost::shared_mutex > lock(*(costmap_->getLock()));
00086   double resolution = costmap_->getResolution();
00087 
00088   grid_.header.frame_id = global_frame_;
00089   grid_.header.stamp = ros::Time::now();
00090   grid_.info.resolution = resolution;
00091 
00092   grid_.info.width = costmap_->getSizeInCellsX();
00093   grid_.info.height = costmap_->getSizeInCellsY();
00094 
00095   double wx, wy;
00096   costmap_->mapToWorld(0, 0, wx, wy);
00097   grid_.info.origin.position.x = wx - resolution / 2;
00098   grid_.info.origin.position.y = wy - resolution / 2;
00099   grid_.info.origin.position.z = 0.0;
00100   grid_.info.origin.orientation.w = 1.0;
00101 
00102   grid_.data.resize(grid_.info.width * grid_.info.height);
00103 
00104   unsigned char* data = costmap_->getCharMap();
00105   for (unsigned int i = 0; i < grid_.data.size(); i++)
00106   {
00107     grid_.data[i] = cost_translation_table_[ data[ i ]];
00108   }
00109 }
00110 
00111 void Costmap2DPublisher::publishCostmap()
00112 {
00113   double resolution = costmap_->getResolution();
00114 
00115   if (always_send_full_costmap_ || grid_.info.resolution != resolution || grid_.info.width != costmap_->getSizeInCellsX())
00116   {
00117     prepareGrid();
00118     if (costmap_pub_.getNumSubscribers() > 0) {
00119       costmap_pub_.publish( grid_ );
00120     }
00121   }
00122   else if (x0_ < xn_)
00123   {
00124     boost::shared_lock < boost::shared_mutex > lock(*(costmap_->getLock()));
00125     
00126     map_msgs::OccupancyGridUpdate update;
00127     update.header.stamp = ros::Time::now();
00128     update.header.frame_id = global_frame_;
00129     update.x = x0_;
00130     update.y = y0_;
00131     update.width = xn_ - x0_;
00132     update.height = yn_ - y0_;
00133     update.data.resize(update.width * update.height);
00134 
00135     unsigned int i = 0;
00136     for (unsigned int y = y0_; y < yn_; y++)
00137     {
00138       for (unsigned int x = x0_; x < xn_; x++)
00139       {
00140         unsigned char cost = costmap_->getCost(x, y);
00141         update.data[i++] = cost_translation_table_[ cost ];
00142       }
00143     }
00144     if (costmap_update_pub_.getNumSubscribers() > 0) {
00145       costmap_update_pub_.publish(update);
00146     }
00147   }
00148 
00149   xn_ = yn_ = 0;
00150   x0_ = costmap_->getSizeInCellsX();
00151   y0_ = costmap_->getSizeInCellsY();
00152 }
00153 
00154 } 
 
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55