occupancy_map_monitor.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Jon Binney */
36 
37 #ifndef MOVEIT_PERCEPTION_OCCUPANCY_MAP_MONITOR_
38 #define MOVEIT_PERCEPTION_OCCUPANCY_MAP_MONITOR_
39 
40 #include <vector>
41 #include <string>
42 #include <ros/ros.h>
43 #include <tf/tf.h>
45 
46 #include <moveit_msgs/SaveMap.h>
47 #include <moveit_msgs/LoadMap.h>
50 
51 #include <boost/thread/mutex.hpp>
52 
53 #include <memory>
54 
55 namespace occupancy_map_monitor
56 {
58 {
59 public:
60  OccupancyMapMonitor(const boost::shared_ptr<tf::Transformer>& tf, const std::string& map_frame = "",
61  double map_resolution = 0.0);
62  OccupancyMapMonitor(double map_resolution = 0.0);
64  const std::string& map_frame = "", double map_resolution = 0.0);
65 
67 
69  void startMonitor();
70 
71  void stopMonitor();
72 
76  {
77  return tree_;
78  }
79 
83  {
84  return tree_const_;
85  }
86 
87  const std::string& getMapFrame() const
88  {
89  return map_frame_;
90  }
91 
92  void setMapFrame(const std::string& frame);
93 
94  double getMapResolution() const
95  {
96  return map_resolution_;
97  }
98 
100  {
101  return tf_;
102  }
103 
104  void addUpdater(const OccupancyMapUpdaterPtr& updater);
105 
108 
110  void forgetShape(ShapeHandle handle);
111 
113  void setUpdateCallback(const boost::function<void()>& update_callback)
114  {
115  tree_->setUpdateCallback(update_callback);
116  }
117 
118  void setTransformCacheCallback(const TransformCacheProvider& transform_cache_callback);
119 
120  void publishDebugInformation(bool flag);
121 
122  bool isActive() const
123  {
124  return active_;
125  }
126 
127 private:
128  void initialize();
129 
131  bool saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response);
132 
134  bool loadMapCallback(moveit_msgs::LoadMap::Request& request, moveit_msgs::LoadMap::Response& response);
135 
136  bool getShapeTransformCache(std::size_t index, const std::string& target_frame, const ros::Time& target_time,
137  ShapeTransformCache& cache) const;
138 
140  std::string map_frame_;
142  boost::mutex parameters_lock_;
143 
146 
147  std::unique_ptr<pluginlib::ClassLoader<OccupancyMapUpdater> > updater_plugin_loader_;
148  std::vector<OccupancyMapUpdaterPtr> map_updaters_;
149  std::vector<std::map<ShapeHandle, ShapeHandle> > mesh_handles_;
152 
153  std::size_t mesh_handle_count_;
154 
159 
160  bool active_;
161 };
162 }
163 
164 #endif
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
std::unique_ptr< pluginlib::ClassLoader< OccupancyMapUpdater > > updater_plugin_loader_
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)
unsigned int index
const boost::shared_ptr< tf::Transformer > & getTFClient() 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.
void addUpdater(const OccupancyMapUpdaterPtr &updater)
void startMonitor()
start the monitor (will begin updating the octomap
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.
std::shared_ptr< const Shape > ShapeConstPtr


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23