pointcloud_moveit_filter.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_PCL_ROS_POINTCLOUD_MOVEIT_FILTER_H_
00038 #define JSK_PCL_ROS_POINTCLOUD_MOVEIT_FILTER_H_
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/version.h>
00046 #include <moveit/occupancy_map_monitor/occupancy_map_updater.h>
00047 #include <moveit/point_containment_filter/shape_mask.h>
00048 #include <moveit/occupancy_map_monitor/occupancy_map_monitor.h>
00049 #include <XmlRpcException.h>
00050 #include <pcl/point_types.h>
00051 #include <pcl/point_cloud.h>
00052 #include <pcl_conversions/pcl_conversions.h>
00053 #include <pcl/filters/extract_indices.h>
00054 
00055 namespace jsk_pcl_ros
00056 {
00057   typedef occupancy_map_monitor::ShapeHandle ShapeHandle;
00058   typedef occupancy_map_monitor::ShapeTransformCache ShapeTransformCache;
00059   class PointCloudMoveitFilter:
00060     public occupancy_map_monitor::OccupancyMapUpdater
00061   {
00062   public:
00063     PointCloudMoveitFilter();
00064     virtual ~PointCloudMoveitFilter();
00065 
00066     virtual bool setParams(XmlRpc::XmlRpcValue &params);
00067     virtual bool initialize();
00068     virtual void start();
00069     virtual void stop();
00070     virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape);
00071     virtual void forgetShape(ShapeHandle handle);
00072     
00073   protected:
00074     virtual void stopHelper();
00075     virtual bool getShapeTransform(ShapeHandle h,
00076                                    Eigen::Affine3d &transform) const;
00077     template <typename PointT>
00078     void cloudMsgCallback(
00079       const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
00080       {
00081         if (monitor_->getMapFrame().empty())
00082           monitor_->setMapFrame(cloud_msg->header.frame_id);
00083         tf::StampedTransform map_H_sensor;
00084         if (monitor_->getMapFrame() == cloud_msg->header.frame_id) {
00085           map_H_sensor.setIdentity();
00086         }
00087         else {
00088           if (tf_) {
00089             try
00090             {
00091               tf_->lookupTransform(monitor_->getMapFrame(),
00092                                    cloud_msg->header.frame_id,
00093                                    cloud_msg->header.stamp,
00094                                    map_H_sensor);
00095             }
00096             catch (tf::TransformException& ex)
00097             {
00098               ROS_ERROR_STREAM("Transform error of sensor data: "
00099                                << ex.what() << "; quitting callback");
00100               return;
00101             }
00102           }
00103           else {
00104             return;
00105           }
00106         }
00107         /* convert cloud message to pcl cloud object */
00108         //typename pcl::PointCloud<PointT>::Ptr cloud(pcl::PointCloud<PointT>);
00109         typename pcl::PointCloud<PointT>::Ptr cloud;
00110         cloud.reset(new pcl::PointCloud<PointT>());
00111         pcl::PointCloud<pcl::PointXYZ> xyz_cloud;
00112         pcl::fromROSMsg(*cloud_msg, *cloud);
00113         pcl::fromROSMsg(*cloud_msg, xyz_cloud);
00114         const tf::Vector3 &sensor_origin_tf = map_H_sensor.getOrigin();
00115         octomap::point3d sensor_origin(
00116           sensor_origin_tf.getX(),
00117           sensor_origin_tf.getY(),
00118           sensor_origin_tf.getZ());
00119         Eigen::Vector3d sensor_origin_eigen(
00120           sensor_origin_tf.getX(),
00121           sensor_origin_tf.getY(),
00122           sensor_origin_tf.getZ());
00123         if (!updateTransformCache(cloud_msg->header.frame_id,
00124                                   cloud_msg->header.stamp))
00125         {
00126           ROS_ERROR_THROTTLE(
00127             1, "Transform cache was not updated. Self-filtering may fail.");
00128           return;
00129         }
00130         /* mask out points on the robot */
00131 #if (MOVEIT_VERSION_MINOR < 6)
00132         shape_mask_->maskContainment(xyz_cloud, sensor_origin_eigen, 0.0,
00133                                      max_range_, mask_);
00134 #else   // from moveit 0.6 (indigo), PCL dependency is removed
00135         shape_mask_->maskContainment(*cloud_msg, sensor_origin_eigen, 0.0,
00136                                      max_range_, mask_);
00137 #endif
00138         typename pcl::PointCloud<PointT>::Ptr
00139           filtered_cloud (new pcl::PointCloud<PointT>);
00140         pcl::PointIndices::Ptr indices (new pcl::PointIndices);
00141         // convert mask into indices
00142         for (size_t i = 0; i < mask_.size(); i++) {
00143           if (mask_[i] == point_containment_filter::ShapeMask::OUTSIDE) {
00144             indices->indices.push_back(i);
00145           }
00146         }
00147         pcl::ExtractIndices<PointT> ex;
00148         ex.setInputCloud(cloud);
00149         ex.setIndices(indices);
00150         ex.setKeepOrganized(keep_organized_);
00151         ex.filter(*filtered_cloud);
00152         sensor_msgs::PointCloud2 ros_cloud;
00153         pcl::toROSMsg(*filtered_cloud, ros_cloud);
00154         ros_cloud.header = cloud_msg->header;
00155         filtered_cloud_publisher_.publish(ros_cloud);
00156       }
00157 
00159     // ROS variables
00161     ros::NodeHandle root_nh_;
00162     ros::NodeHandle private_nh_;
00163     boost::shared_ptr<tf::Transformer> tf_;
00164     std::string point_cloud_topic_;
00165     double scale_;
00166     double padding_;
00167     double max_range_;
00168     unsigned int point_subsample_;
00169     std::string filtered_cloud_topic_;
00170     ros::Publisher filtered_cloud_publisher_;
00171 
00172     message_filters::Subscriber<sensor_msgs::PointCloud2> *point_cloud_subscriber_;
00173     tf::MessageFilter<sensor_msgs::PointCloud2> *point_cloud_filter_;
00174 
00175     boost::scoped_ptr<point_containment_filter::ShapeMask> shape_mask_;
00176     std::vector<int> mask_;
00177 
00178     bool use_color_;
00179     bool keep_organized_;
00180     
00181   private:
00182     
00183   };
00184 }
00185 
00186 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50