pointcloud_octomap_updater.cpp
Go to the documentation of this file.
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 #include <moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h>
00038 #include <moveit/occupancy_map_monitor/occupancy_map_monitor.h>
00039 #include <message_filters/subscriber.h>
00040 #include <pcl/ros/conversions.h>
00041 #include <XmlRpcException.h>
00042 
00043 namespace occupancy_map_monitor
00044 {
00045 
00046 PointCloudOctomapUpdater::PointCloudOctomapUpdater() : OccupancyMapUpdater("PointCloudUpdater"),
00047                                                        scale_(1.0),
00048                                                        padding_(0.0),
00049                                                        max_range_(std::numeric_limits<double>::infinity()),
00050                                                        point_subsample_(1),
00051                                                        point_cloud_subscriber_(NULL),
00052                                                        point_cloud_filter_(NULL),
00053                                private_nh_("~")
00054 {
00055 }
00056 
00057 PointCloudOctomapUpdater::~PointCloudOctomapUpdater()
00058 {
00059   stopHelper();
00060 }
00061 
00062 bool PointCloudOctomapUpdater::setParams(XmlRpc::XmlRpcValue &params)
00063 {
00064   try
00065   {
00066     if (!params.hasMember("point_cloud_topic"))
00067       return false;
00068     point_cloud_topic_ = static_cast<const std::string&>(params["point_cloud_topic"]);
00069 
00070     readXmlParam(params, "max_range", &max_range_);
00071     readXmlParam(params, "shape_padding", &padding_);
00072     readXmlParam(params, "shape_scale", &scale_);
00073     readXmlParam(params, "point_subsample", &point_subsample_);
00074     if (params.hasMember("filtered_cloud_topic"))
00075       filtered_cloud_topic_ = static_cast<const std::string&>(params["filtered_cloud_topic"]);
00076   }
00077   catch (XmlRpc::XmlRpcException &ex)
00078   {
00079     ROS_ERROR("XmlRpc Exception: %s", ex.getMessage().c_str());
00080     return false;
00081   }
00082 
00083   return true;
00084 }
00085 
00086 bool PointCloudOctomapUpdater::initialize()
00087 {
00088   tf_ = monitor_->getTFClient();
00089   shape_mask_.reset(new point_containment_filter::ShapeMask());
00090   shape_mask_->setTransformCallback(boost::bind(&PointCloudOctomapUpdater::getShapeTransform, this, _1, _2));
00091   if (!filtered_cloud_topic_.empty())
00092     filtered_cloud_publisher_ = private_nh_.advertise<sensor_msgs::PointCloud2>(filtered_cloud_topic_, 10, false);
00093   return true;
00094 }
00095 
00096 void PointCloudOctomapUpdater::start()
00097 {
00098   if (point_cloud_subscriber_)
00099     return;
00100   /* subscribe to point cloud topic using tf filter*/
00101   point_cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::PointCloud2>(root_nh_, point_cloud_topic_, 5);
00102   if (tf_ && !monitor_->getMapFrame().empty())
00103   {
00104     point_cloud_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(*point_cloud_subscriber_, *tf_, monitor_->getMapFrame(), 5);
00105     point_cloud_filter_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1));
00106     ROS_INFO("Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(), point_cloud_filter_->getTargetFramesString().c_str());
00107   }
00108   else
00109   {
00110     point_cloud_subscriber_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1));
00111     ROS_INFO("Listening to '%s'", point_cloud_topic_.c_str());
00112   }
00113 }
00114 
00115 void PointCloudOctomapUpdater::stopHelper()
00116 {
00117   delete point_cloud_filter_;
00118   delete point_cloud_subscriber_;
00119 }
00120 
00121 void PointCloudOctomapUpdater::stop()
00122 {
00123   stopHelper();
00124   point_cloud_filter_ = NULL;
00125   point_cloud_subscriber_ = NULL;
00126 }
00127 
00128 ShapeHandle PointCloudOctomapUpdater::excludeShape(const shapes::ShapeConstPtr &shape)
00129 {
00130   ShapeHandle h = 0;
00131   if (shape_mask_)
00132     h = shape_mask_->addShape(shape, scale_, padding_);
00133   else
00134     ROS_ERROR("Shape filter not yet initialized!");
00135   return h;
00136 }
00137 
00138 void PointCloudOctomapUpdater::forgetShape(ShapeHandle handle)
00139 {
00140   if (shape_mask_)
00141     shape_mask_->removeShape(handle);
00142 }
00143 
00144 bool PointCloudOctomapUpdater::getShapeTransform(ShapeHandle h, Eigen::Affine3d &transform) const
00145 {
00146   ShapeTransformCache::const_iterator it = transform_cache_.find(h);
00147   if (it == transform_cache_.end())
00148   {
00149     ROS_ERROR("Internal error. Shape filter handle %u not found", h);
00150     return false;
00151   }
00152   transform = it->second;
00153   return true;
00154 }
00155 
00156 void PointCloudOctomapUpdater::updateMask(const pcl::PointCloud<pcl::PointXYZ> &cloud, const Eigen::Vector3d &sensor_origin, std::vector<int> &mask)
00157 {
00158 }
00159 
00160 void PointCloudOctomapUpdater::cloudMsgCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
00161 {
00162   ROS_DEBUG("Received a new point cloud message");
00163   ros::WallTime start = ros::WallTime::now();
00164 
00165   if (monitor_->getMapFrame().empty())
00166     monitor_->setMapFrame(cloud_msg->header.frame_id);
00167 
00168   /* get transform for cloud into map frame */
00169   tf::StampedTransform map_H_sensor;
00170   if (monitor_->getMapFrame() == cloud_msg->header.frame_id)
00171     map_H_sensor.setIdentity();
00172   else
00173   {
00174     if (tf_)
00175     {
00176       try
00177       {
00178         tf_->lookupTransform(monitor_->getMapFrame(), cloud_msg->header.frame_id, cloud_msg->header.stamp, map_H_sensor);
00179       }
00180       catch (tf::TransformException& ex)
00181       {
00182         ROS_ERROR_STREAM("Transform error of sensor data: " << ex.what() << "; quitting callback");
00183         return;
00184       }
00185     }
00186     else
00187       return;
00188   }
00189 
00190   /* convert cloud message to pcl cloud object */
00191   pcl::PointCloud<pcl::PointXYZ> cloud;
00192   pcl::fromROSMsg(*cloud_msg, cloud);
00193 
00194   /* compute sensor origin in map frame */
00195   const tf::Vector3 &sensor_origin_tf = map_H_sensor.getOrigin();
00196   octomap::point3d sensor_origin(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
00197   Eigen::Vector3d sensor_origin_eigen(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
00198 
00199   if (!updateTransformCache(cloud_msg->header.frame_id, cloud_msg->header.stamp))
00200   {
00201     ROS_ERROR_THROTTLE(1, "Transform cache was not updated. Self-filtering may fail.");
00202     return;
00203   }
00204 
00205   /* mask out points on the robot */
00206   shape_mask_->maskContainment(cloud, sensor_origin_eigen, 0.0, max_range_, mask_);
00207   updateMask(cloud, sensor_origin_eigen, mask_);
00208 
00209   octomap::KeySet free_cells, occupied_cells, model_cells, clip_cells;
00210   boost::scoped_ptr<pcl::PointCloud<pcl::PointXYZ> > filtered_cloud;
00211   if (!filtered_cloud_topic_.empty())
00212     filtered_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>());
00213 
00214   tree_->lockRead();
00215 
00216   try
00217   {
00218     /* do ray tracing to find which cells this point cloud indicates should be free, and which it indicates
00219      * should be occupied */
00220     for (unsigned int row = 0; row < cloud.height; row += point_subsample_)
00221     {
00222       unsigned int row_c = row * cloud.width;
00223       for (unsigned int col = 0; col < cloud.width; col += point_subsample_)
00224       {
00225         //if (mask_[row_c + col] == point_containment_filter::ShapeMask::CLIP)
00226         //  continue;
00227         const pcl::PointXYZ &p = cloud(col, row);
00228 
00229         /* check for NaN */
00230         if ((p.x == p.x) && (p.y == p.y) && (p.z == p.z))
00231     {
00232       /* transform to map frame */
00233       tf::Vector3 point_tf = map_H_sensor * tf::Vector3(p.x, p.y, p.z);
00234 
00235       /* occupied cell at ray endpoint if ray is shorter than max range and this point
00236          isn't on a part of the robot*/
00237       if (mask_[row_c + col] == point_containment_filter::ShapeMask::INSIDE)
00238         model_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
00239       else if (mask_[row_c + col] == point_containment_filter::ShapeMask::CLIP)
00240         clip_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
00241       else
00242           {
00243             occupied_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
00244             if (filtered_cloud)
00245               filtered_cloud->push_back(p);
00246           }
00247         }
00248       }
00249     }
00250 
00251     /* compute the free cells along each ray that ends at an occupied cell */
00252     for (octomap::KeySet::iterator it = occupied_cells.begin(), end = occupied_cells.end(); it != end; ++it)
00253       if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(*it), key_ray_))
00254         free_cells.insert(key_ray_.begin(), key_ray_.end());
00255 
00256     /* compute the free cells along each ray that ends at a model cell */
00257     for (octomap::KeySet::iterator it = model_cells.begin(), end = model_cells.end(); it != end; ++it)
00258       if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(*it), key_ray_))
00259         free_cells.insert(key_ray_.begin(), key_ray_.end());
00260 
00261     /* compute the free cells along each ray that ends at a clipped cell */
00262     for (octomap::KeySet::iterator it = clip_cells.begin(), end = clip_cells.end(); it != end; ++it)
00263       if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(*it), key_ray_))
00264         free_cells.insert(key_ray_.begin(), key_ray_.end());
00265   }
00266   catch (...)
00267   {
00268     tree_->unlockRead();
00269     return;
00270   }
00271 
00272   tree_->unlockRead();
00273 
00274   /* cells that overlap with the model are not occupied */
00275   for (octomap::KeySet::iterator it = model_cells.begin(), end = model_cells.end(); it != end; ++it)
00276     occupied_cells.erase(*it);
00277 
00278   /* occupied cells are not free */
00279   for (octomap::KeySet::iterator it = occupied_cells.begin(), end = occupied_cells.end(); it != end; ++it)
00280     free_cells.erase(*it);
00281 
00282   tree_->lockWrite();
00283 
00284   try
00285   {
00286     /* mark free cells only if not seen occupied in this cloud */
00287     for (octomap::KeySet::iterator it = free_cells.begin(), end = free_cells.end(); it != end; ++it)
00288       tree_->updateNode(*it, false);
00289 
00290     /* now mark all occupied cells */
00291     for (octomap::KeySet::iterator it = occupied_cells.begin(), end = occupied_cells.end(); it != end; ++it)
00292       tree_->updateNode(*it, true);
00293 
00294     // set the logodds to the minimum for the cells that are part of the model
00295     const float lg = tree_->getClampingThresMinLog() - tree_->getClampingThresMaxLog();
00296     for (octomap::KeySet::iterator it = model_cells.begin(), end = model_cells.end(); it != end; ++it)
00297       tree_->updateNode(*it, lg);
00298   }
00299   catch (...)
00300   {
00301     ROS_ERROR("Internal error while updating octree");
00302   }
00303   tree_->unlockWrite();
00304   ROS_DEBUG("Processed point cloud in %lf ms", (ros::WallTime::now() - start).toSec() * 1000.0);
00305   tree_->triggerUpdateCallback();
00306 
00307   if (filtered_cloud)
00308   {
00309     sensor_msgs::PointCloud2 filtered_cloud_msg;
00310     pcl::toROSMsg(*filtered_cloud, filtered_cloud_msg);
00311     filtered_cloud_msg.header = cloud_msg->header;
00312     filtered_cloud_publisher_.publish(filtered_cloud_msg);
00313   }
00314 }
00315 
00316 }


perception
Author(s): Ioan Sucan , Jon Binney
autogenerated on Mon Oct 6 2014 02:31:20