pointcloud_moveit_filter.cpp
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 #include <jsk_topic_tools/log_utils.h>
00036 #include "jsk_pcl_ros/pointcloud_moveit_filter.h"
00037 
00038 namespace jsk_pcl_ros
00039 {
00040   PointCloudMoveitFilter::PointCloudMoveitFilter():
00041     OccupancyMapUpdater("PointCloudMoveitFilter"),
00042     private_nh_("~"),
00043     scale_(1.0),
00044     padding_(0.0),
00045     max_range_(std::numeric_limits<double>::infinity()),
00046     point_subsample_(1),
00047     point_cloud_subscriber_(NULL),
00048     point_cloud_filter_(NULL),
00049     use_color_(false),
00050     keep_organized_(false)
00051   {
00052   }
00053 
00054   PointCloudMoveitFilter::~PointCloudMoveitFilter()
00055   {
00056   }
00057 
00058   bool PointCloudMoveitFilter::setParams(XmlRpc::XmlRpcValue &params)
00059   {
00060     try
00061     {
00062       if (!params.hasMember("point_cloud_topic"))
00063         return false;
00064       point_cloud_topic_ = static_cast<const std::string&>(params["point_cloud_topic"]);
00065       
00066       readXmlParam(params, "max_range", &max_range_);
00067       readXmlParam(params, "padding_offset", &padding_);
00068       readXmlParam(params, "padding_scale", &scale_);
00069       readXmlParam(params, "point_subsample", &point_subsample_);
00070       if (!params.hasMember("filtered_cloud_topic")) {
00071         ROS_ERROR("filtered_cloud_topic is required");
00072         return false;
00073       }
00074       else {
00075         filtered_cloud_topic_ = static_cast<const std::string&>(params["filtered_cloud_topic"]);
00076       }
00077       if (params.hasMember("filtered_cloud_use_color")) {
00078         use_color_ = (bool)params["filtered_cloud_use_color"];
00079       }
00080       if (params.hasMember("filtered_cloud_keep_organized")) {
00081         keep_organized_ = (bool)params["filtered_cloud_keep_organized"];
00082       }
00083     }
00084     catch (XmlRpc::XmlRpcException& ex)
00085     {
00086       ROS_ERROR("XmlRpc Exception: %s", ex.getMessage().c_str());
00087       return false;
00088     }
00089     
00090     return true;
00091   }
00092 
00093 
00094   
00095   bool PointCloudMoveitFilter::initialize()
00096   {
00097     tf_ = monitor_->getTFClient();
00098     shape_mask_.reset(new point_containment_filter::ShapeMask());
00099     shape_mask_->setTransformCallback(
00100       boost::bind(&PointCloudMoveitFilter::getShapeTransform, this, _1, _2));
00101     filtered_cloud_publisher_ = private_nh_.advertise<sensor_msgs::PointCloud2>(
00102       filtered_cloud_topic_, 10, false);
00103     return true;
00104   }
00105 
00106   bool PointCloudMoveitFilter::getShapeTransform(ShapeHandle h, Eigen::Affine3d &transform) const
00107   {
00108     ShapeTransformCache::const_iterator it = transform_cache_.find(h);
00109     if (it == transform_cache_.end())
00110     {
00111       ROS_ERROR("Internal error. Shape filter handle %u not found", h);
00112       return false;
00113     }
00114     transform = it->second;
00115     return true;
00116   }
00117 
00118   ShapeHandle PointCloudMoveitFilter::excludeShape(const shapes::ShapeConstPtr &shape)
00119   {
00120     ShapeHandle h = 0;
00121     if (shape_mask_)
00122       h = shape_mask_->addShape(shape, scale_, padding_);
00123     else
00124       ROS_ERROR("Shape filter not yet initialized!");
00125     return h;
00126   }
00127 
00128   
00129   void PointCloudMoveitFilter::forgetShape(ShapeHandle handle)
00130   {
00131     if (shape_mask_)
00132       shape_mask_->removeShape(handle);
00133   }
00134 
00135   
00136   void PointCloudMoveitFilter::start()
00137   {
00138     if (point_cloud_subscriber_)
00139       return;
00140     /* subscribe to point cloud topic using tf filter*/
00141     point_cloud_subscriber_
00142       = new message_filters::Subscriber<sensor_msgs::PointCloud2>(
00143         root_nh_, point_cloud_topic_, 5);
00144     if (tf_ && !monitor_->getMapFrame().empty())
00145     {
00146       point_cloud_filter_
00147         = new tf::MessageFilter<sensor_msgs::PointCloud2>(
00148           *point_cloud_subscriber_, *tf_, monitor_->getMapFrame(), 5);
00149       if (use_color_) {
00150         point_cloud_filter_->registerCallback(
00151           boost::bind(
00152             &PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZRGB>,
00153             this, _1));
00154       }
00155       else {
00156         point_cloud_filter_->registerCallback(
00157           boost::bind(
00158             &PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZ>,
00159             this, _1));
00160       }
00161       ROS_INFO("Listening to '%s' using message filter with target frame '%s'",
00162                point_cloud_topic_.c_str(),
00163                point_cloud_filter_->getTargetFramesString().c_str());
00164     }
00165     else
00166     {
00167       if (use_color_) {
00168         point_cloud_subscriber_->registerCallback(
00169           boost::bind(
00170             &PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZRGB>,
00171             this, _1));
00172       }
00173       else {
00174         point_cloud_subscriber_->registerCallback(
00175           boost::bind(&PointCloudMoveitFilter::cloudMsgCallback<pcl::PointXYZ>,
00176                       this, _1));
00177       }
00178       ROS_INFO("Listening to '%s'", point_cloud_topic_.c_str());
00179     }
00180   }
00181 
00182   void PointCloudMoveitFilter::stopHelper()
00183   {
00184     delete point_cloud_filter_;
00185     delete point_cloud_subscriber_;
00186   }
00187   
00188   void PointCloudMoveitFilter::stop()
00189   {
00190     stopHelper();
00191     point_cloud_filter_ = NULL;
00192     point_cloud_subscriber_ = NULL;
00193   }
00194   
00195 }
00196 
00197 #include <class_loader/class_loader.h>
00198 CLASS_LOADER_REGISTER_CLASS(jsk_pcl_ros::PointCloudMoveitFilter, occupancy_map_monitor::OccupancyMapUpdater)


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