#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. | |
void | forgetShape (ShapeHandle handle) |
Forget about this shape handle and the shapes it corresponds to. | |
const std::string & | getMapFrame () const |
double | getMapResolution () const |
const OccMapTreePtr & | getOcTreePtr () |
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. | |
const OccMapTreeConstPtr & | getOcTreePtr () const |
Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this pointer. | |
const boost::shared_ptr < tf::Transformer > & | getTFClient () const |
bool | isActive () const |
OccupancyMapMonitor (const boost::shared_ptr< tf::Transformer > &tf, 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. | |
void | startMonitor () |
start the monitor (will begin updating the octomap | |
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) | |
bool | saveMapCallback (moveit_msgs::SaveMap::Request &request, moveit_msgs::SaveMap::Response &response) |
Save the current octree to a binary file. | |
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_ |
boost::shared_ptr < tf::Transformer > | tf_ |
TransformCacheProvider | transform_cache_callback_ |
OccMapTreePtr | tree_ |
OccMapTreeConstPtr | tree_const_ |
boost::scoped_ptr < pluginlib::ClassLoader < OccupancyMapUpdater > > | updater_plugin_loader_ |
Definition at line 56 of file occupancy_map_monitor.h.
occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor | ( | const boost::shared_ptr< tf::Transformer > & | tf, |
const std::string & | map_frame = "" , |
||
double | map_resolution = 0.0 |
||
) |
Definition at line 57 of file occupancy_map_monitor.cpp.
occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor | ( | double | map_resolution = 0.0 | ) |
Definition at line 47 of file occupancy_map_monitor.cpp.
Definition at line 333 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::addUpdater | ( | const OccupancyMapUpdaterPtr & | updater | ) |
Definition at line 171 of file occupancy_map_monitor.cpp.
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 208 of file occupancy_map_monitor.cpp.
Forget about this shape handle and the shapes it corresponds to.
Definition at line 228 of file occupancy_map_monitor.cpp.
const std::string& occupancy_map_monitor::OccupancyMapMonitor::getMapFrame | ( | ) | const [inline] |
Definition at line 85 of file occupancy_map_monitor.h.
double occupancy_map_monitor::OccupancyMapMonitor::getMapResolution | ( | ) | const [inline] |
Definition at line 92 of file occupancy_map_monitor.h.
const 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 73 of file occupancy_map_monitor.h.
const 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 80 of file occupancy_map_monitor.h.
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 255 of file occupancy_map_monitor.cpp.
const boost::shared_ptr<tf::Transformer>& occupancy_map_monitor::OccupancyMapMonitor::getTFClient | ( | ) | const [inline] |
Definition at line 97 of file occupancy_map_monitor.h.
void occupancy_map_monitor::OccupancyMapMonitor::initialize | ( | ) | [private] |
Definition at line 68 of file occupancy_map_monitor.cpp.
bool occupancy_map_monitor::OccupancyMapMonitor::isActive | ( | ) | const [inline] |
Definition at line 120 of file occupancy_map_monitor.h.
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 298 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::publishDebugInformation | ( | bool | flag | ) |
Definition at line 195 of file occupancy_map_monitor.cpp.
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 282 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::setMapFrame | ( | const std::string & | frame | ) |
Definition at line 202 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::setTransformCacheCallback | ( | const TransformCacheProvider & | transform_cache_callback | ) |
Definition at line 246 of file occupancy_map_monitor.cpp.
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 111 of file occupancy_map_monitor.h.
start the monitor (will begin updating the octomap
Definition at line 318 of file occupancy_map_monitor.cpp.
Definition at line 326 of file occupancy_map_monitor.cpp.
bool occupancy_map_monitor::OccupancyMapMonitor::active_ [private] |
Definition at line 158 of file occupancy_map_monitor.h.
bool occupancy_map_monitor::OccupancyMapMonitor::debug_info_ [private] |
Definition at line 149 of file occupancy_map_monitor.h.
Definition at line 156 of file occupancy_map_monitor.h.
std::string occupancy_map_monitor::OccupancyMapMonitor::map_frame_ [private] |
Definition at line 138 of file occupancy_map_monitor.h.
double occupancy_map_monitor::OccupancyMapMonitor::map_resolution_ [private] |
Definition at line 139 of file occupancy_map_monitor.h.
std::vector<OccupancyMapUpdaterPtr> occupancy_map_monitor::OccupancyMapMonitor::map_updaters_ [private] |
Definition at line 146 of file occupancy_map_monitor.h.
std::size_t occupancy_map_monitor::OccupancyMapMonitor::mesh_handle_count_ [private] |
Definition at line 151 of file occupancy_map_monitor.h.
std::vector<std::map<ShapeHandle, ShapeHandle> > occupancy_map_monitor::OccupancyMapMonitor::mesh_handles_ [private] |
Definition at line 147 of file occupancy_map_monitor.h.
Definition at line 154 of file occupancy_map_monitor.h.
boost::mutex occupancy_map_monitor::OccupancyMapMonitor::parameters_lock_ [private] |
Definition at line 140 of file occupancy_map_monitor.h.
Definition at line 153 of file occupancy_map_monitor.h.
Definition at line 155 of file occupancy_map_monitor.h.
boost::shared_ptr<tf::Transformer> occupancy_map_monitor::OccupancyMapMonitor::tf_ [private] |
Definition at line 137 of file occupancy_map_monitor.h.
TransformCacheProvider occupancy_map_monitor::OccupancyMapMonitor::transform_cache_callback_ [private] |
Definition at line 148 of file occupancy_map_monitor.h.
Definition at line 142 of file occupancy_map_monitor.h.
Definition at line 143 of file occupancy_map_monitor.h.
boost::scoped_ptr<pluginlib::ClassLoader<OccupancyMapUpdater> > occupancy_map_monitor::OccupancyMapMonitor::updater_plugin_loader_ [private] |
Definition at line 145 of file occupancy_map_monitor.h.