pointcloud_octomap_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: Jon Binney, Ioan Sucan */
36 
37 #ifndef MOVEIT_PERCEPTION_POINTCLOUD_OCTOMAP_UPDATER_
38 #define MOVEIT_PERCEPTION_POINTCLOUD_OCTOMAP_UPDATER_
39 
40 #include <ros/ros.h>
41 #include <tf/tf.h>
42 #include <tf/message_filter.h>
44 #include <sensor_msgs/PointCloud2.h>
47 
48 #include <memory>
49 
50 namespace occupancy_map_monitor
51 {
53 {
54 public:
56  virtual ~PointCloudOctomapUpdater();
57 
58  virtual bool setParams(XmlRpc::XmlRpcValue& params);
59 
60  virtual bool initialize();
61  virtual void start();
62  virtual void stop();
63  virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape);
64  virtual void forgetShape(ShapeHandle handle);
65 
66 protected:
67  virtual void updateMask(const sensor_msgs::PointCloud2& cloud, const Eigen::Vector3d& sensor_origin,
68  std::vector<int>& mask);
69 
70 private:
71  bool getShapeTransform(ShapeHandle h, Eigen::Affine3d& transform) const;
72  void cloudMsgCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
73  void stopHelper();
74 
78 
80 
81  /* params */
82  std::string point_cloud_topic_;
83  double scale_;
84  double padding_;
85  double max_range_;
86  unsigned int point_subsample_;
88  std::string filtered_cloud_topic_;
90 
93 
94  /* used to store all cells in the map which a given ray passes through during raycasting.
95  we cache this here because it dynamically pre-allocates a lot of memory in its contsructor */
97 
98  std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
99  std::vector<int> mask_;
100 };
101 }
102 
103 #endif
virtual bool initialize()
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
std::unique_ptr< point_containment_filter::ShapeMask > shape_mask_
Base class for classes which update the occupancy map.
message_filters::Subscriber< sensor_msgs::PointCloud2 > * point_cloud_subscriber_
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
bool getShapeTransform(ShapeHandle h, Eigen::Affine3d &transform) const
virtual void updateMask(const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector3d &sensor_origin, std::vector< int > &mask)
void cloudMsgCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual bool setParams(XmlRpc::XmlRpcValue &params)
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
std::shared_ptr< const Shape > ShapeConstPtr
tf::MessageFilter< sensor_msgs::PointCloud2 > * point_cloud_filter_


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Wed Jul 10 2019 04:03:27