shape_mask.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* Author: Ioan Sucan */
00031 
00032 #include <moveit/point_containment_filter/shape_mask.h>
00033 #include <geometric_shapes/body_operations.h>
00034 #include <ros/console.h>
00035 
00036 point_containment_filter::ShapeMask::ShapeMask(const TransformCallback& transform_callback) :
00037   transform_callback_(transform_callback),
00038   next_handle_ (1),
00039   min_handle_ (1)
00040 {
00041 }
00042 
00043 point_containment_filter::ShapeMask::~ShapeMask()
00044 {
00045   freeMemory();
00046 }
00047 
00048 void point_containment_filter::ShapeMask::freeMemory()
00049 {
00050   for (std::set<SeeShape>::const_iterator it = bodies_.begin() ; it != bodies_.end() ; ++it)
00051     delete it->body;
00052   bodies_.clear();
00053 }
00054 
00055 void point_containment_filter::ShapeMask::setTransformCallback(const TransformCallback& transform_callback)
00056 {
00057   boost::mutex::scoped_lock _(shapes_lock_);
00058   transform_callback_ = transform_callback;
00059 }
00060 
00061 point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addShape(const shapes::ShapeConstPtr &shape, double scale, double padding)
00062 {
00063   boost::mutex::scoped_lock _(shapes_lock_);
00064   SeeShape ss;
00065   ss.body = bodies::createBodyFromShape(shape.get());
00066   if (ss.body)
00067   {
00068     ss.body->setScale(scale);
00069     ss.body->setPadding(padding);
00070     ss.volume = ss.body->computeVolume();
00071     ss.handle = next_handle_;
00072     std::pair<std::set<SeeShape, SortBodies>::iterator, bool> insert_op = bodies_.insert(ss);
00073     if (!insert_op.second)
00074       ROS_ERROR("Internal error in management of bodies in ShapeMask. This is a serious error.");
00075     used_handles_[next_handle_] = insert_op.first;
00076   }
00077   else
00078     return 0;
00079 
00080   ShapeHandle ret = next_handle_;
00081   const std::size_t sz = min_handle_ + bodies_.size() + 1;
00082   for (std::size_t i = min_handle_ ; i < sz ; ++i)
00083     if (used_handles_.find(i) == used_handles_.end())
00084     {
00085       next_handle_ = i;
00086       break;
00087     }
00088   min_handle_ = next_handle_;
00089 
00090   return ret;
00091 }
00092 
00093 void point_containment_filter::ShapeMask::removeShape(ShapeHandle handle)
00094 {
00095   boost::mutex::scoped_lock _(shapes_lock_);
00096   std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator>::iterator it = used_handles_.find(handle);
00097   if (it != used_handles_.end())
00098   {
00099     delete it->second->body;
00100     bodies_.erase(it->second);
00101     used_handles_.erase(it);
00102     min_handle_ = handle;
00103   }
00104   else
00105     ROS_ERROR("Unable to remove shape handle %u", handle);
00106 }
00107 
00108 void point_containment_filter::ShapeMask::maskContainment(const pcl::PointCloud<pcl::PointXYZ>& data_in,
00109                                                           const Eigen::Vector3d &sensor_origin,
00110                                                           const double min_sensor_dist, const double max_sensor_dist,
00111                                                           std::vector<int> &mask)
00112 {
00113   boost::mutex::scoped_lock _(shapes_lock_);
00114   mask.resize(data_in.points.size());
00115   if (bodies_.empty())
00116     std::fill(mask.begin(), mask.end(), (int)OUTSIDE);
00117   else
00118   {
00119     Eigen::Affine3d tmp;
00120     bspheres_.resize(bodies_.size());
00121     std::size_t j = 0;
00122     for (std::set<SeeShape>::const_iterator it = bodies_.begin() ; it != bodies_.end() ; ++it)
00123     {
00124       if (transform_callback_(it->handle, tmp))
00125       {
00126         it->body->setPose(tmp);
00127         it->body->computeBoundingSphere(bspheres_[j++]);
00128       }
00129     }
00130 
00131     const unsigned int np = data_in.points.size();
00132 
00133     // compute a sphere that bounds the entire robot
00134     bodies::BoundingSphere bound;
00135     bodies::mergeBoundingSpheres(bspheres_, bound);
00136     const double radiusSquared = bound.radius * bound.radius;
00137 
00138     // we now decide which points we keep
00139 #pragma omp parallel for schedule(dynamic)
00140     for (int i = 0 ; i < (int)np ; ++i)
00141     {
00142       Eigen::Vector3d pt = Eigen::Vector3d(data_in.points[i].x, data_in.points[i].y, data_in.points[i].z);
00143       double d = pt.norm();
00144       int out = OUTSIDE;
00145       if (d < min_sensor_dist || d > max_sensor_dist)
00146         out = CLIP;
00147       else
00148         if ((bound.center - pt).squaredNorm() < radiusSquared)
00149           for (std::set<SeeShape>::const_iterator it = bodies_.begin() ; it != bodies_.end() && out == OUTSIDE ; ++it)
00150             if (it->body->containsPoint(pt))
00151               out = INSIDE;
00152       mask[i] = out;
00153     }
00154   }
00155 }
00156 
00157 int point_containment_filter::ShapeMask::getMaskContainment(const Eigen::Vector3d &pt) const
00158 {
00159   boost::mutex::scoped_lock _(shapes_lock_);
00160 
00161   int out = OUTSIDE;
00162   for (std::set<SeeShape>::const_iterator it = bodies_.begin() ; it != bodies_.end() && out == OUTSIDE ; ++it)
00163     if (it->body->containsPoint(pt))
00164       out = INSIDE;
00165   return out;
00166 }
00167 
00168 int point_containment_filter::ShapeMask::getMaskContainment(double x, double y, double z) const
00169 {
00170   return getMaskContainment(Eigen::Vector3d(x, y, z));
00171 }


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