Public Member Functions | Private Member Functions | Private Attributes | List of all members
occupancy_map_monitor::OccupancyMapMonitor Class Reference

#include <occupancy_map_monitor.h>

Public Member Functions

void addUpdater (const OccupancyMapUpdaterPtr &updater)
 
ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape)
 Add this shape to the set of shapes to be filtered out from the octomap. More...
 
void forgetShape (ShapeHandle handle)
 Forget about this shape handle and the shapes it corresponds to. More...
 
const std::string & getMapFrame () const
 
double getMapResolution () const
 
const collision_detection::OccMapTreePtrgetOcTreePtr ()
 Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing using this pointer. The value of this pointer stays the same throughout the existance of the monitor instance. More...
 
const collision_detection::OccMapTreeConstPtrgetOcTreePtr () const
 Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this pointer. More...
 
const std::shared_ptr< tf2_ros::Buffer > & getTFClient () const
 
bool isActive () const
 
 OccupancyMapMonitor (const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const std::string &map_frame="", double map_resolution=0.0)
 
 OccupancyMapMonitor (const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, ros::NodeHandle &nh, const std::string &map_frame="", double map_resolution=0.0)
 
 OccupancyMapMonitor (double map_resolution=0.0)
 
void publishDebugInformation (bool flag)
 
void setMapFrame (const std::string &frame)
 
void setTransformCacheCallback (const TransformCacheProvider &transform_cache_callback)
 
void setUpdateCallback (const boost::function< void()> &update_callback)
 Set the callback to trigger when updates to the maintained octomap are received. More...
 
void startMonitor ()
 start the monitor (will begin updating the octomap More...
 
void stopMonitor ()
 
 ~OccupancyMapMonitor ()
 

Private Member Functions

bool getShapeTransformCache (std::size_t index, const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache) const
 
void initialize ()
 
bool loadMapCallback (moveit_msgs::LoadMap::Request &request, moveit_msgs::LoadMap::Response &response)
 Load octree from a binary file (gets rid of current octree data) More...
 
bool saveMapCallback (moveit_msgs::SaveMap::Request &request, moveit_msgs::SaveMap::Response &response)
 Save the current octree to a binary file. More...
 

Private Attributes

bool active_
 
bool debug_info_
 
ros::ServiceServer load_map_srv_
 
std::string map_frame_
 
double map_resolution_
 
std::vector< OccupancyMapUpdaterPtr > map_updaters_
 
std::size_t mesh_handle_count_
 
std::vector< std::map< ShapeHandle, ShapeHandle > > mesh_handles_
 
ros::NodeHandle nh_
 
boost::mutex parameters_lock_
 
ros::NodeHandle root_nh_
 
ros::ServiceServer save_map_srv_
 
std::shared_ptr< tf2_ros::Buffertf_buffer_
 
TransformCacheProvider transform_cache_callback_
 
collision_detection::OccMapTreePtr tree_
 
collision_detection::OccMapTreeConstPtr tree_const_
 
std::unique_ptr< pluginlib::ClassLoader< OccupancyMapUpdater > > updater_plugin_loader_
 

Detailed Description

Definition at line 88 of file occupancy_map_monitor.h.

Constructor & Destructor Documentation

◆ OccupancyMapMonitor() [1/3]

occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor ( const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer,
const std::string &  map_frame = "",
double  map_resolution = 0.0 
)

Definition at line 86 of file occupancy_map_monitor.cpp.

◆ OccupancyMapMonitor() [2/3]

occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor ( double  map_resolution = 0.0)

Definition at line 80 of file occupancy_map_monitor.cpp.

◆ OccupancyMapMonitor() [3/3]

occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor ( const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer,
ros::NodeHandle nh,
const std::string &  map_frame = "",
double  map_resolution = 0.0 
)

Definition at line 98 of file occupancy_map_monitor.cpp.

◆ ~OccupancyMapMonitor()

occupancy_map_monitor::OccupancyMapMonitor::~OccupancyMapMonitor ( )

Definition at line 402 of file occupancy_map_monitor.cpp.

Member Function Documentation

◆ addUpdater()

void occupancy_map_monitor::OccupancyMapMonitor::addUpdater ( const OccupancyMapUpdaterPtr &  updater)

Definition at line 223 of file occupancy_map_monitor.cpp.

◆ excludeShape()

ShapeHandle occupancy_map_monitor::OccupancyMapMonitor::excludeShape ( const shapes::ShapeConstPtr shape)

Add this shape to the set of shapes to be filtered out from the octomap.

Definition at line 271 of file occupancy_map_monitor.cpp.

◆ forgetShape()

void occupancy_map_monitor::OccupancyMapMonitor::forgetShape ( ShapeHandle  handle)

Forget about this shape handle and the shapes it corresponds to.

Definition at line 291 of file occupancy_map_monitor.cpp.

◆ getMapFrame()

const std::string& occupancy_map_monitor::OccupancyMapMonitor::getMapFrame ( ) const
inline

Definition at line 150 of file occupancy_map_monitor.h.

◆ getMapResolution()

double occupancy_map_monitor::OccupancyMapMonitor::getMapResolution ( ) const
inline

Definition at line 157 of file occupancy_map_monitor.h.

◆ getOcTreePtr() [1/2]

const collision_detection::OccMapTreePtr& occupancy_map_monitor::OccupancyMapMonitor::getOcTreePtr ( )
inline

Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing using this pointer. The value of this pointer stays the same throughout the existance of the monitor instance.

Definition at line 138 of file occupancy_map_monitor.h.

◆ getOcTreePtr() [2/2]

const collision_detection::OccMapTreeConstPtr& occupancy_map_monitor::OccupancyMapMonitor::getOcTreePtr ( ) const
inline

Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this pointer.

Definition at line 145 of file occupancy_map_monitor.h.

◆ getShapeTransformCache()

bool occupancy_map_monitor::OccupancyMapMonitor::getShapeTransformCache ( std::size_t  index,
const std::string &  target_frame,
const ros::Time target_time,
ShapeTransformCache cache 
) const
private

Definition at line 318 of file occupancy_map_monitor.cpp.

◆ getTFClient()

const std::shared_ptr<tf2_ros::Buffer>& occupancy_map_monitor::OccupancyMapMonitor::getTFClient ( ) const
inline

Definition at line 162 of file occupancy_map_monitor.h.

◆ initialize()

void occupancy_map_monitor::OccupancyMapMonitor::initialize ( )
private

Definition at line 110 of file occupancy_map_monitor.cpp.

◆ isActive()

bool occupancy_map_monitor::OccupancyMapMonitor::isActive ( ) const
inline

Definition at line 185 of file occupancy_map_monitor.h.

◆ loadMapCallback()

bool occupancy_map_monitor::OccupancyMapMonitor::loadMapCallback ( moveit_msgs::LoadMap::Request &  request,
moveit_msgs::LoadMap::Response &  response 
)
private

Load octree from a binary file (gets rid of current octree data)

Definition at line 363 of file occupancy_map_monitor.cpp.

◆ publishDebugInformation()

void occupancy_map_monitor::OccupancyMapMonitor::publishDebugInformation ( bool  flag)

Definition at line 258 of file occupancy_map_monitor.cpp.

◆ saveMapCallback()

bool occupancy_map_monitor::OccupancyMapMonitor::saveMapCallback ( moveit_msgs::SaveMap::Request &  request,
moveit_msgs::SaveMap::Response &  response 
)
private

Save the current octree to a binary file.

Definition at line 346 of file occupancy_map_monitor.cpp.

◆ setMapFrame()

void occupancy_map_monitor::OccupancyMapMonitor::setMapFrame ( const std::string &  frame)

Definition at line 265 of file occupancy_map_monitor.cpp.

◆ setTransformCacheCallback()

void occupancy_map_monitor::OccupancyMapMonitor::setTransformCacheCallback ( const TransformCacheProvider transform_cache_callback)

Definition at line 309 of file occupancy_map_monitor.cpp.

◆ setUpdateCallback()

void occupancy_map_monitor::OccupancyMapMonitor::setUpdateCallback ( const boost::function< void()> &  update_callback)
inline

Set the callback to trigger when updates to the maintained octomap are received.

Definition at line 176 of file occupancy_map_monitor.h.

◆ startMonitor()

void occupancy_map_monitor::OccupancyMapMonitor::startMonitor ( )

start the monitor (will begin updating the octomap

Definition at line 387 of file occupancy_map_monitor.cpp.

◆ stopMonitor()

void occupancy_map_monitor::OccupancyMapMonitor::stopMonitor ( )

Definition at line 395 of file occupancy_map_monitor.cpp.

Member Data Documentation

◆ active_

bool occupancy_map_monitor::OccupancyMapMonitor::active_
private

Definition at line 223 of file occupancy_map_monitor.h.

◆ debug_info_

bool occupancy_map_monitor::OccupancyMapMonitor::debug_info_
private

Definition at line 214 of file occupancy_map_monitor.h.

◆ load_map_srv_

ros::ServiceServer occupancy_map_monitor::OccupancyMapMonitor::load_map_srv_
private

Definition at line 221 of file occupancy_map_monitor.h.

◆ map_frame_

std::string occupancy_map_monitor::OccupancyMapMonitor::map_frame_
private

Definition at line 203 of file occupancy_map_monitor.h.

◆ map_resolution_

double occupancy_map_monitor::OccupancyMapMonitor::map_resolution_
private

Definition at line 204 of file occupancy_map_monitor.h.

◆ map_updaters_

std::vector<OccupancyMapUpdaterPtr> occupancy_map_monitor::OccupancyMapMonitor::map_updaters_
private

Definition at line 211 of file occupancy_map_monitor.h.

◆ mesh_handle_count_

std::size_t occupancy_map_monitor::OccupancyMapMonitor::mesh_handle_count_
private

Definition at line 216 of file occupancy_map_monitor.h.

◆ mesh_handles_

std::vector<std::map<ShapeHandle, ShapeHandle> > occupancy_map_monitor::OccupancyMapMonitor::mesh_handles_
private

Definition at line 212 of file occupancy_map_monitor.h.

◆ nh_

ros::NodeHandle occupancy_map_monitor::OccupancyMapMonitor::nh_
private

Definition at line 219 of file occupancy_map_monitor.h.

◆ parameters_lock_

boost::mutex occupancy_map_monitor::OccupancyMapMonitor::parameters_lock_
private

Definition at line 205 of file occupancy_map_monitor.h.

◆ root_nh_

ros::NodeHandle occupancy_map_monitor::OccupancyMapMonitor::root_nh_
private

Definition at line 218 of file occupancy_map_monitor.h.

◆ save_map_srv_

ros::ServiceServer occupancy_map_monitor::OccupancyMapMonitor::save_map_srv_
private

Definition at line 220 of file occupancy_map_monitor.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> occupancy_map_monitor::OccupancyMapMonitor::tf_buffer_
private

Definition at line 202 of file occupancy_map_monitor.h.

◆ transform_cache_callback_

TransformCacheProvider occupancy_map_monitor::OccupancyMapMonitor::transform_cache_callback_
private

Definition at line 213 of file occupancy_map_monitor.h.

◆ tree_

collision_detection::OccMapTreePtr occupancy_map_monitor::OccupancyMapMonitor::tree_
private

Definition at line 207 of file occupancy_map_monitor.h.

◆ tree_const_

collision_detection::OccMapTreeConstPtr occupancy_map_monitor::OccupancyMapMonitor::tree_const_
private

Definition at line 208 of file occupancy_map_monitor.h.

◆ updater_plugin_loader_

std::unique_ptr<pluginlib::ClassLoader<OccupancyMapUpdater> > occupancy_map_monitor::OccupancyMapMonitor::updater_plugin_loader_
private

Definition at line 210 of file occupancy_map_monitor.h.


The documentation for this class was generated from the following files:


occupancy_map_monitor
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sat Apr 27 2024 02:25:59