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 #pragma once
38 
39 #include <vector>
40 #include <string>
41 #include <ros/ros.h>
42 #include <tf2_ros/buffer.h>
44 
45 #include <moveit_msgs/SaveMap.h>
46 #include <moveit_msgs/LoadMap.h>
49 
50 #include <boost/thread/mutex.hpp>
51 
52 #include <memory>
53 
55 {
57 {
58 public:
59  OccupancyMapMonitor(const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const std::string& map_frame = "",
60  double map_resolution = 0.0);
61  OccupancyMapMonitor(double map_resolution = 0.0);
62  OccupancyMapMonitor(const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, ros::NodeHandle& nh,
63  const std::string& map_frame = "", double map_resolution = 0.0);
64 
66 
68  void startMonitor();
69 
70  void stopMonitor();
71 
75  {
76  return tree_;
77  }
78 
82  {
83  return tree_const_;
84  }
85 
86  const std::string& getMapFrame() const
87  {
88  return map_frame_;
89  }
90 
91  void setMapFrame(const std::string& frame);
92 
93  double getMapResolution() const
94  {
95  return map_resolution_;
96  }
97 
98  const std::shared_ptr<tf2_ros::Buffer>& getTFClient() const
99  {
100  return tf_buffer_;
101  }
102 
103  void addUpdater(const OccupancyMapUpdaterPtr& updater);
104 
107 
109  void forgetShape(ShapeHandle handle);
110 
112  void setUpdateCallback(const boost::function<void()>& update_callback)
113  {
114  tree_->setUpdateCallback(update_callback);
115  }
116 
117  void setTransformCacheCallback(const TransformCacheProvider& transform_cache_callback);
118 
119  void publishDebugInformation(bool flag);
120 
121  bool isActive() const
122  {
123  return active_;
124  }
125 
126 private:
127  void initialize();
128 
130  bool saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response);
131 
133  bool loadMapCallback(moveit_msgs::LoadMap::Request& request, moveit_msgs::LoadMap::Response& response);
134 
135  bool getShapeTransformCache(std::size_t index, const std::string& target_frame, const ros::Time& target_time,
136  ShapeTransformCache& cache) const;
137 
138  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
139  std::string map_frame_;
140  double map_resolution_;
141  boost::mutex parameters_lock_;
142 
145 
146  std::unique_ptr<pluginlib::ClassLoader<OccupancyMapUpdater> > updater_plugin_loader_;
147  std::vector<OccupancyMapUpdaterPtr> map_updaters_;
148  std::vector<std::map<ShapeHandle, ShapeHandle> > mesh_handles_;
151 
152  std::size_t mesh_handle_count_;
153 
158 
159  bool active_;
160 };
161 } // namespace occupancy_map_monitor
occupancy_map_monitor::OccupancyMapMonitor::stopMonitor
void stopMonitor()
Definition: occupancy_map_monitor.cpp:395
occupancy_map_monitor::OccupancyMapMonitor::root_nh_
ros::NodeHandle root_nh_
Definition: occupancy_map_monitor.h:218
occupancy_map_monitor::OccupancyMapMonitor::map_frame_
std::string map_frame_
Definition: occupancy_map_monitor.h:203
occupancy_map_monitor::OccupancyMapMonitor::getShapeTransformCache
bool getShapeTransformCache(std::size_t index, const std::string &target_frame, const ros::Time &target_time, ShapeTransformCache &cache) const
Definition: occupancy_map_monitor.cpp:318
occupancy_map_monitor::ShapeTransformCache
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
Definition: occupancy_map_updater.h:81
collision_detection::OccMapTreeConstPtr
std::shared_ptr< const OccMapTree > OccMapTreeConstPtr
occupancy_map_monitor::OccupancyMapMonitor::nh_
ros::NodeHandle nh_
Definition: occupancy_map_monitor.h:219
occupancy_map_monitor::OccupancyMapMonitor::isActive
bool isActive() const
Definition: occupancy_map_monitor.h:185
occupancy_map_monitor::OccupancyMapMonitor::mesh_handle_count_
std::size_t mesh_handle_count_
Definition: occupancy_map_monitor.h:216
occupancy_map_monitor::OccupancyMapMonitor::updater_plugin_loader_
std::unique_ptr< pluginlib::ClassLoader< OccupancyMapUpdater > > updater_plugin_loader_
Definition: occupancy_map_monitor.h:210
occupancy_map_monitor::OccupancyMapMonitor
Definition: occupancy_map_monitor.h:88
ros.h
occupancy_map_monitor::OccupancyMapMonitor::parameters_lock_
boost::mutex parameters_lock_
Definition: occupancy_map_monitor.h:205
occupancy_map_monitor::OccupancyMapMonitor::getTFClient
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
Definition: occupancy_map_monitor.h:162
occupancy_map_monitor::OccupancyMapMonitor::getMapResolution
double getMapResolution() const
Definition: occupancy_map_monitor.h:157
occupancy_map_monitor::OccupancyMapMonitor::transform_cache_callback_
TransformCacheProvider transform_cache_callback_
Definition: occupancy_map_monitor.h:213
occupancy_map_monitor::OccupancyMapMonitor::initialize
void initialize()
Definition: occupancy_map_monitor.cpp:110
buffer.h
occupancy_map_monitor::OccupancyMapMonitor::debug_info_
bool debug_info_
Definition: occupancy_map_monitor.h:214
occupancy_map_monitor::OccupancyMapMonitor::saveMapCallback
bool saveMapCallback(moveit_msgs::SaveMap::Request &request, moveit_msgs::SaveMap::Response &response)
Save the current octree to a binary file.
Definition: occupancy_map_monitor.cpp:346
occupancy_map_monitor::OccupancyMapMonitor::getMapFrame
const std::string & getMapFrame() const
Definition: occupancy_map_monitor.h:150
occupancy_map_monitor::OccupancyMapMonitor::addUpdater
void addUpdater(const OccupancyMapUpdaterPtr &updater)
Definition: occupancy_map_monitor.cpp:223
occupancy_map_monitor::OccupancyMapMonitor::save_map_srv_
ros::ServiceServer save_map_srv_
Definition: occupancy_map_monitor.h:220
occupancy_map_monitor::OccupancyMapMonitor::~OccupancyMapMonitor
~OccupancyMapMonitor()
Definition: occupancy_map_monitor.cpp:402
ros::ServiceServer
occupancy_map_monitor::OccupancyMapMonitor::active_
bool active_
Definition: occupancy_map_monitor.h:223
occupancy_map_monitor::OccupancyMapMonitor::startMonitor
void startMonitor()
start the monitor (will begin updating the octomap
Definition: occupancy_map_monitor.cpp:387
occupancy_map_monitor::OccupancyMapMonitor::loadMapCallback
bool loadMapCallback(moveit_msgs::LoadMap::Request &request, moveit_msgs::LoadMap::Response &response)
Load octree from a binary file (gets rid of current octree data)
Definition: occupancy_map_monitor.cpp:363
occupancy_map_monitor::OccupancyMapMonitor::setMapFrame
void setMapFrame(const std::string &frame)
Definition: occupancy_map_monitor.cpp:265
occupancy_map_monitor::OccupancyMapMonitor::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: occupancy_map_monitor.h:202
occupancy_map_monitor::OccupancyMapMonitor::load_map_srv_
ros::ServiceServer load_map_srv_
Definition: occupancy_map_monitor.h:221
occupancy_map_monitor::TransformCacheProvider
boost::function< bool(const std::string &, const ros::Time &, ShapeTransformCache &)> TransformCacheProvider
Definition: occupancy_map_updater.h:82
occupancy_map_monitor::OccupancyMapMonitor::publishDebugInformation
void publishDebugInformation(bool flag)
Definition: occupancy_map_monitor.cpp:258
occupancy_map_monitor::OccupancyMapMonitor::setUpdateCallback
void setUpdateCallback(const boost::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
Definition: occupancy_map_monitor.h:176
class_loader.hpp
occupancy_map_monitor::OccupancyMapMonitor::forgetShape
void forgetShape(ShapeHandle handle)
Forget about this shape handle and the shapes it corresponds to.
Definition: occupancy_map_monitor.cpp:291
occupancy_map_monitor::OccupancyMapMonitor::getOcTreePtr
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
Definition: occupancy_map_monitor.h:138
occupancy_map_monitor::ShapeHandle
unsigned int ShapeHandle
Definition: occupancy_map_updater.h:79
occupancy_map_updater.h
occupancy_map_monitor::OccupancyMapMonitor::mesh_handles_
std::vector< std::map< ShapeHandle, ShapeHandle > > mesh_handles_
Definition: occupancy_map_monitor.h:212
ros::Time
tf_buffer
tf2_ros::Buffer * tf_buffer
occupancy_map_monitor
Definition: occupancy_map_monitor.h:54
occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor
OccupancyMapMonitor(const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const std::string &map_frame="", double map_resolution=0.0)
Definition: occupancy_map_monitor.cpp:86
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
occupancy_map_monitor::OccupancyMapMonitor::tree_
collision_detection::OccMapTreePtr tree_
Definition: occupancy_map_monitor.h:207
occupancy_map_monitor::OccupancyMapMonitor::map_resolution_
double map_resolution_
Definition: occupancy_map_monitor.h:204
occupancy_map_monitor::OccupancyMapMonitor::setTransformCacheCallback
void setTransformCacheCallback(const TransformCacheProvider &transform_cache_callback)
Definition: occupancy_map_monitor.cpp:309
collision_detection::OccMapTreePtr
std::shared_ptr< OccMapTree > OccMapTreePtr
occupancy_map_monitor::OccupancyMapMonitor::map_updaters_
std::vector< OccupancyMapUpdaterPtr > map_updaters_
Definition: occupancy_map_monitor.h:211
occupancy_map_monitor::OccupancyMapMonitor::excludeShape
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
Add this shape to the set of shapes to be filtered out from the octomap.
Definition: occupancy_map_monitor.cpp:271
occupancy_map_monitor::OccupancyMapMonitor::tree_const_
collision_detection::OccMapTreeConstPtr tree_const_
Definition: occupancy_map_monitor.h:208
occupancy_map.h
ros::NodeHandle


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