occupancy_map_updater.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_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_UPDATER_
38 #define MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_UPDATER_
39 
43 #include <Eigen/Core>
44 #include <Eigen/Geometry>
45 
46 namespace occupancy_map_monitor
47 {
48 typedef unsigned int ShapeHandle;
49 typedef std::map<ShapeHandle, Eigen::Isometry3d, std::less<ShapeHandle>,
50  Eigen::aligned_allocator<std::pair<const ShapeHandle, Eigen::Isometry3d> > >
52 typedef boost::function<bool(const std::string& target_frame, const ros::Time& target_time, ShapeTransformCache& cache)>
54 
56 
57 MOVEIT_CLASS_FORWARD(OccupancyMapUpdater); // Defines OccupancyMapUpdaterPtr, ConstPtr, WeakPtr... etc
58 
62 {
63 public:
64  OccupancyMapUpdater(const std::string& type);
65  virtual ~OccupancyMapUpdater();
66 
68  void setMonitor(OccupancyMapMonitor* monitor);
69 
72  virtual bool setParams(XmlRpc::XmlRpcValue& params) = 0;
73 
76  virtual bool initialize() = 0;
77 
78  virtual void start() = 0;
79 
80  virtual void stop() = 0;
81 
82  virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape) = 0;
83 
84  virtual void forgetShape(ShapeHandle handle) = 0;
85 
86  const std::string& getType() const
87  {
88  return type_;
89  }
90 
91  void setTransformCacheCallback(const TransformCacheProvider& transform_callback)
92  {
93  transform_provider_callback_ = transform_callback;
94  }
95 
96  void publishDebugInformation(bool flag)
97  {
98  debug_info_ = flag;
99  }
100 
101 protected:
103  std::string type_;
108 
109  bool updateTransformCache(const std::string& target_frame, const ros::Time& target_time);
110 
111  static void readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, double* value);
112  static void readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, unsigned int* value);
113 };
114 } // namespace occupancy_map_monitor
115 
116 #endif
std::shared_ptr< OccMapTree > OccMapTreePtr
Base class for classes which update the occupancy map.
virtual void forgetShape(ShapeHandle handle)=0
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)=0
virtual bool initialize()=0
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
void setTransformCacheCallback(const TransformCacheProvider &transform_callback)
MOVEIT_CLASS_FORWARD(OccupancyMapUpdater)
void setMonitor(OccupancyMapMonitor *monitor)
This is the first function to be called after construction.
boost::function< bool(const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache)> TransformCacheProvider
static void readXmlParam(XmlRpc::XmlRpcValue &params, const std::string &param_name, double *value)
bool updateTransformCache(const std::string &target_frame, const ros::Time &target_time)
virtual bool setParams(XmlRpc::XmlRpcValue &params)=0
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
std::shared_ptr< const Shape > ShapeConstPtr


occupancy_map_monitor
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Wed May 5 2021 02:53:56