00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Jon Binney, Ioan Sucan */ 00036 00037 #ifndef MOVEIT_PERCEPTION_POINTCLOUD_OCTOMAP_UPDATER_ 00038 #define MOVEIT_PERCEPTION_POINTCLOUD_OCTOMAP_UPDATER_ 00039 00040 #include <ros/ros.h> 00041 #include <tf/tf.h> 00042 #include <tf/message_filter.h> 00043 #include <message_filters/subscriber.h> 00044 #include <sensor_msgs/PointCloud2.h> 00045 #include <moveit/occupancy_map_monitor/occupancy_map_updater.h> 00046 #include <moveit/point_containment_filter/shape_mask.h> 00047 #include <pcl/point_types.h> 00048 #include <pcl/point_cloud.h> 00049 00050 namespace occupancy_map_monitor 00051 { 00052 00053 class PointCloudOctomapUpdater : public OccupancyMapUpdater 00054 { 00055 public: 00056 00057 PointCloudOctomapUpdater(); 00058 virtual ~PointCloudOctomapUpdater(); 00059 00060 virtual bool setParams(XmlRpc::XmlRpcValue ¶ms); 00061 00062 virtual bool initialize(); 00063 virtual void start(); 00064 virtual void stop(); 00065 virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape); 00066 virtual void forgetShape(ShapeHandle handle); 00067 00068 protected: 00069 00070 virtual void updateMask(const pcl::PointCloud<pcl::PointXYZ> &cloud, const Eigen::Vector3d &sensor_origin, std::vector<int> &mask); 00071 00072 private: 00073 00074 bool getShapeTransform(ShapeHandle h, Eigen::Affine3d &transform) const; 00075 void cloudMsgCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg); 00076 void stopHelper(); 00077 00078 ros::NodeHandle root_nh_; 00079 ros::NodeHandle private_nh_; 00080 boost::shared_ptr<tf::Transformer> tf_; 00081 00082 /* params */ 00083 std::string point_cloud_topic_; 00084 double scale_; 00085 double padding_; 00086 double max_range_; 00087 unsigned int point_subsample_; 00088 std::string filtered_cloud_topic_; 00089 ros::Publisher filtered_cloud_publisher_; 00090 00091 message_filters::Subscriber<sensor_msgs::PointCloud2> *point_cloud_subscriber_; 00092 tf::MessageFilter<sensor_msgs::PointCloud2> *point_cloud_filter_; 00093 00094 /* used to store all cells in the map which a given ray passes through during raycasting. 00095 we cache this here because it dynamically pre-allocates a lot of memory in its contsructor */ 00096 octomap::KeyRay key_ray_; 00097 00098 boost::scoped_ptr<point_containment_filter::ShapeMask> shape_mask_; 00099 std::vector<int> mask_; 00100 00101 }; 00102 00103 } 00104 00105 #endif