37 #ifndef MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_UPDATER_    38 #define MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_UPDATER_    43 #include <boost/shared_ptr.hpp>    45 #include <Eigen/Geometry>    50 typedef std::map<ShapeHandle, Eigen::Affine3d, std::less<ShapeHandle>,
    51                  Eigen::aligned_allocator<std::pair<const ShapeHandle, Eigen::Affine3d> > >
    53 typedef boost::function<bool(const std::string& target_frame, const ros::Time& target_time, ShapeTransformCache& cache)>
    79   virtual void start() = 0;
    81   virtual void stop() = 0;
 std::map< ShapeHandle, Eigen::Affine3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Affine3d > > > ShapeTransformCache
OccupancyMapMonitor * monitor_
std::shared_ptr< OccMapTree > OccMapTreePtr
virtual ~OccupancyMapUpdater()
Base class for classes which update the occupancy map. 
virtual void forgetShape(ShapeHandle handle)=0
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)=0
virtual bool initialize()=0
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
void publishDebugInformation(bool flag)
TransformCacheProvider transform_provider_callback_
OccupancyMapUpdater(const std::string &type)
void setTransformCacheCallback(const TransformCacheProvider &transform_callback)
MOVEIT_CLASS_FORWARD(OccupancyMapUpdater)
void setMonitor(OccupancyMapMonitor *monitor)
This is the first function to be called after construction. 
boost::function< bool(const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache)> TransformCacheProvider
static void readXmlParam(XmlRpc::XmlRpcValue ¶ms, const std::string ¶m_name, double *value)
const std::string & getType() const 
bool updateTransformCache(const std::string &target_frame, const ros::Time &target_time)
ShapeTransformCache transform_cache_
virtual bool setParams(XmlRpc::XmlRpcValue ¶ms)=0
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
std::shared_ptr< const Shape > ShapeConstPtr