37 #ifndef MOVEIT_PERCEPTION_OCCUPANCY_MAP_MONITOR_ 38 #define MOVEIT_PERCEPTION_OCCUPANCY_MAP_MONITOR_ 46 #include <moveit_msgs/SaveMap.h> 47 #include <moveit_msgs/LoadMap.h> 51 #include <boost/thread/mutex.hpp> 61 double map_resolution = 0.0);
64 const std::string& map_frame =
"",
double map_resolution = 0.0);
104 void addUpdater(
const OccupancyMapUpdaterPtr& updater);
115 tree_->setUpdateCallback(update_callback);
131 bool saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response);
134 bool loadMapCallback(moveit_msgs::LoadMap::Request& request, moveit_msgs::LoadMap::Response& response);
std::map< ShapeHandle, Eigen::Affine3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Affine3d > > > ShapeTransformCache
void setTransformCacheCallback(const TransformCacheProvider &transform_cache_callback)
std::shared_ptr< OccMapTree > OccMapTreePtr
ros::ServiceServer save_map_srv_
ros::ServiceServer load_map_srv_
void setMapFrame(const std::string &frame)
std::unique_ptr< pluginlib::ClassLoader< OccupancyMapUpdater > > updater_plugin_loader_
std::size_t mesh_handle_count_
std::shared_ptr< const OccMapTree > OccMapTreeConstPtr
boost::shared_ptr< tf::Transformer > tf_
std::vector< std::map< ShapeHandle, ShapeHandle > > mesh_handles_
bool loadMapCallback(moveit_msgs::LoadMap::Request &request, moveit_msgs::LoadMap::Response &response)
Load octree from a binary file (gets rid of current octree data)
boost::mutex parameters_lock_
void publishDebugInformation(bool flag)
const boost::shared_ptr< tf::Transformer > & getTFClient() const
const std::string & getMapFrame() const
bool saveMapCallback(moveit_msgs::SaveMap::Request &request, moveit_msgs::SaveMap::Response &response)
Save the current octree to a binary file.
void forgetShape(ShapeHandle handle)
Forget about this shape handle and the shapes it corresponds to.
OccMapTreeConstPtr tree_const_
void addUpdater(const OccupancyMapUpdaterPtr &updater)
void startMonitor()
start the monitor (will begin updating the octomap
TransformCacheProvider transform_cache_callback_
const OccMapTreeConstPtr & getOcTreePtr() const
Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this poin...
const OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
boost::function< bool(const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache)> TransformCacheProvider
std::vector< OccupancyMapUpdaterPtr > map_updaters_
bool getShapeTransformCache(std::size_t index, const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache) const
void setUpdateCallback(const boost::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
OccupancyMapMonitor(const boost::shared_ptr< tf::Transformer > &tf, const std::string &map_frame="", double map_resolution=0.0)
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
Add this shape to the set of shapes to be filtered out from the octomap.
double getMapResolution() const
std::shared_ptr< const Shape > ShapeConstPtr