58 CostmapAdapter::~CostmapAdapter()
60 if (needs_destruction_)
68 costmap_ros_ = costmap_ros;
69 needs_destruction_ = needs_destruction;
71 costmap_ = costmap_ros_->getCostmap();
81 return costmap_->getMutex();
84 void CostmapAdapter::reset()
86 costmap_->resetMap(0, 0, costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
89 void CostmapAdapter::update()
92 if (!costmap_ros_->isCurrent())
96 void CostmapAdapter::setValue(
const unsigned int x,
const unsigned int y,
const unsigned char& value)
98 costmap_->setCost(x, y, value);
101 unsigned char CostmapAdapter::getValue(
const unsigned int x,
const unsigned int y)
const 103 unsigned int index = costmap_->getIndex(x, y);
104 return costmap_->getCharMap()[index];
nav_grid::NavGridInfo infoFromCostmap(costmap_2d::Costmap2DROS *costmap_ros)
ROSCONSOLE_DECL void initialize()
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double getOriginX() const
boost::recursive_mutex mutex_t
double getOriginY() const
unsigned int getSizeInCellsY() const
unsigned int getSizeInCellsX() const
double getResolution() const
std::shared_ptr< tf::TransformListener > TFListenerPtr