42 static const std::string 
LOGNAME = 
"occupancy_map_monitor";
 
   48 OccupancyMapUpdater::~OccupancyMapUpdater() = 
default;
 
   50 void OccupancyMapUpdater::setMonitor(OccupancyMapMonitor* monitor)
 
   53   tree_ = monitor->getOcTreePtr();
 
   56 void OccupancyMapUpdater::readXmlParam(
XmlRpc::XmlRpcValue& params, 
const std::string& param_name, 
double* value)
 
   61       *value = (int)params[param_name];
 
   63       *value = (double)params[param_name];
 
   67 void OccupancyMapUpdater::readXmlParam(
XmlRpc::XmlRpcValue& params, 
const std::string& param_name, 
unsigned int* value)
 
   70     *value = (int)params[param_name];
 
   73 bool OccupancyMapUpdater::updateTransformCache(
const std::string& target_frame, 
const ros::Time& target_time)
 
   75   transform_cache_.clear();
 
   76   if (transform_provider_callback_)
 
   78     bool success = transform_provider_callback_(target_frame, target_time, transform_cache_);
 
   82           "Transform cache was not updated. Self-filtering may fail. If transforms were not available yet, consider " 
   83           "setting robot_description_planning/shape_transform_cache_lookup_wait_time to wait longer for transforms");