Go to the documentation of this file.
43 #include <Eigen/Geometry>
48 using ShapeTransformCache = std::map<ShapeHandle, Eigen::Isometry3d, std::less<ShapeHandle>,
49 Eigen::aligned_allocator<std::pair<const ShapeHandle, Eigen::Isometry3d> > >;
52 class OccupancyMapMonitor;
58 class OccupancyMapUpdater
75 virtual void start() = 0;
77 virtual void stop() = 0;
83 const std::string&
getType()
const
void publishDebugInformation(bool flag)
OccupancyMapUpdater(const std::string &type)
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
void setMonitor(OccupancyMapMonitor *monitor)
This is the first function to be called after construction.
MOVEIT_CLASS_FORWARD(OccupancyMapUpdater)
static void readXmlParam(XmlRpc::XmlRpcValue ¶ms, const std::string ¶m_name, double *value)
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...
ShapeTransformCache transform_cache_
bool updateTransformCache(const std::string &target_frame, const ros::Time &target_time)
boost::function< bool(const std::string &, const ros::Time &, ShapeTransformCache &)> TransformCacheProvider
virtual void forgetShape(ShapeHandle handle)=0
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)=0
collision_detection::OccMapTreePtr tree_
virtual bool initialize()=0
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
virtual ~OccupancyMapUpdater()
const std::string & getType() const
std::shared_ptr< const Shape > ShapeConstPtr
OccupancyMapMonitor * monitor_
void setTransformCacheCallback(const TransformCacheProvider &transform_callback)
std::shared_ptr< OccMapTree > OccMapTreePtr
TransformCacheProvider transform_provider_callback_
occupancy_map_monitor
Author(s): Ioan Sucan
, Jon Binney , Suat Gedikli
autogenerated on Thu Nov 21 2024 03:24:13