Go to the documentation of this file.
45 #include <moveit_msgs/SaveMap.h>
46 #include <moveit_msgs/LoadMap.h>
50 #include <boost/thread/mutex.hpp>
60 double map_resolution = 0.0);
63 const std::string& map_frame =
"",
double map_resolution = 0.0);
98 const std::shared_ptr<tf2_ros::Buffer>&
getTFClient()
const
103 void addUpdater(
const OccupancyMapUpdaterPtr& updater);
114 tree_->setUpdateCallback(update_callback);
130 bool saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response);
133 bool loadMapCallback(moveit_msgs::LoadMap::Request& request, moveit_msgs::LoadMap::Response& response);
148 std::vector<std::map<ShapeHandle, ShapeHandle> >
mesh_handles_;
bool getShapeTransformCache(std::size_t index, const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache) const
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
std::shared_ptr< const OccMapTree > OccMapTreeConstPtr
std::size_t mesh_handle_count_
std::unique_ptr< pluginlib::ClassLoader< OccupancyMapUpdater > > updater_plugin_loader_
boost::mutex parameters_lock_
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
double getMapResolution() const
TransformCacheProvider transform_cache_callback_
bool saveMapCallback(moveit_msgs::SaveMap::Request &request, moveit_msgs::SaveMap::Response &response)
Save the current octree to a binary file.
const std::string & getMapFrame() const
void addUpdater(const OccupancyMapUpdaterPtr &updater)
ros::ServiceServer save_map_srv_
void startMonitor()
start the monitor (will begin updating the octomap
bool loadMapCallback(moveit_msgs::LoadMap::Request &request, moveit_msgs::LoadMap::Response &response)
Load octree from a binary file (gets rid of current octree data)
void setMapFrame(const std::string &frame)
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
ros::ServiceServer load_map_srv_
boost::function< bool(const std::string &, const ros::Time &, ShapeTransformCache &)> TransformCacheProvider
void publishDebugInformation(bool flag)
void setUpdateCallback(const boost::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
void forgetShape(ShapeHandle handle)
Forget about this shape handle and the shapes it corresponds to.
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
std::vector< std::map< ShapeHandle, ShapeHandle > > mesh_handles_
tf2_ros::Buffer * tf_buffer
OccupancyMapMonitor(const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const std::string &map_frame="", double map_resolution=0.0)
std::shared_ptr< const Shape > ShapeConstPtr
collision_detection::OccMapTreePtr tree_
void setTransformCacheCallback(const TransformCacheProvider &transform_cache_callback)
std::shared_ptr< OccMapTree > OccMapTreePtr
std::vector< OccupancyMapUpdaterPtr > map_updaters_
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
Add this shape to the set of shapes to be filtered out from the octomap.
collision_detection::OccMapTreeConstPtr tree_const_
occupancy_map_monitor
Author(s): Ioan Sucan
, Jon Binney , Suat Gedikli
autogenerated on Sat Apr 27 2024 02:25:59