cylinder.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 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_recognition_utils/geo/cylinder.h"
00039 #include "jsk_recognition_utils/geo_util.h"
00040 
00041 namespace jsk_recognition_utils
00042 {
00043   Cylinder::Cylinder(Eigen::Vector3f point, Eigen::Vector3f direction, double radius):
00044     point_(point), direction_(direction), radius_(radius)
00045   {
00046 
00047   }
00048 
00049   void Cylinder::filterPointCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud,
00050                                   const double threshold,
00051                                   pcl::PointIndices& output)
00052   {
00053     Line line(direction_, point_);
00054     output.indices.clear();
00055     for (size_t i = 0; i < cloud.points.size(); i++) {
00056       Eigen::Vector3f p = cloud.points[i].getVector3fMap();
00057       double d = line.distanceToPoint(p);
00058       if (d < radius_ + threshold && d > radius_ - threshold) {
00059         output.indices.push_back(i);
00060       }
00061     }
00062   }
00063 
00064   void Cylinder::estimateCenterAndHeight(const pcl::PointCloud<pcl::PointXYZ>& cloud,
00065                                          const pcl::PointIndices& indices,
00066                                          Eigen::Vector3f& center,
00067                                          double& height)
00068   {
00069     Line line(direction_, point_);
00070     Vertices points;
00071     for (size_t i = 0; i < indices.indices.size(); i++) {
00072       int point_index = indices.indices[i];
00073       points.push_back(cloud.points[point_index].getVector3fMap());
00074     }
00075     PointPair min_max = line.findEndPoints(points);
00076     Eigen::Vector3f min_point = min_max.get<0>();
00077     Eigen::Vector3f max_point = min_max.get<1>();
00078     Eigen::Vector3f min_point_projected, max_point_projected;
00079     line.foot(min_point, min_point_projected);
00080     line.foot(max_point, max_point_projected);
00081     height = (min_point_projected - max_point_projected).norm();
00082     center = (min_point_projected + max_point_projected) / 2.0;
00083   }
00084 
00085   void Cylinder::toMarker(visualization_msgs::Marker& marker,
00086                           const Eigen::Vector3f& center,
00087                           const Eigen::Vector3f& uz,
00088                           const double height)
00089   {
00090     marker.type = visualization_msgs::Marker::CYLINDER;
00091     marker.pose.position.x = center[0];
00092     marker.pose.position.y = center[1];
00093     marker.pose.position.z = center[2];
00094     Eigen::Vector3f orig_z(0, 0, 1);
00095     Eigen::Quaternionf q;
00096     q.setFromTwoVectors(orig_z, uz);
00097     marker.pose.orientation.x = q.x();
00098     marker.pose.orientation.y = q.y();
00099     marker.pose.orientation.z = q.z();
00100     marker.pose.orientation.w = q.w();
00101     marker.scale.x = radius_ * 2;
00102     marker.scale.y = radius_ * 2;
00103     marker.scale.z = height;
00104     marker.color.a = 1.0;
00105     marker.color.g = 1.0;
00106     marker.color.b = 1.0;
00107   }
00108 
00109   Eigen::Vector3f Cylinder::getDirection()
00110   {
00111     return direction_;
00112   }
00113 
00114 }


jsk_recognition_utils
Author(s):
autogenerated on Wed Sep 16 2015 04:36:01