geo_util.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 #ifndef JSK_RECOGNITION_UTILS_GEO_UTIL_H_
00037 #define JSK_RECOGNITION_UTILS_GEO_UTIL_H_
00038 //#define BOOST_PARAMETER_MAX_ARITY 7 
00039 
00040 #include <Eigen/Core>
00041 #include <Eigen/Geometry>
00042 #include <Eigen/StdVector>
00043 
00044 #include <vector>
00045 
00046 #include <boost/shared_ptr.hpp>
00047 #include <boost/thread.hpp>
00048 #include <geometry_msgs/Polygon.h>
00049 #include <jsk_recognition_msgs/BoundingBox.h>
00050 #include <jsk_recognition_msgs/SimpleOccupancyGrid.h>
00051 #include <boost/tuple/tuple.hpp>
00052 
00054 // PCL headers
00056 #include <pcl/point_types.h>
00057 #include <pcl/point_cloud.h>
00058 #include <pcl/PointIndices.h>
00059 #include <pcl/filters/extract_indices.h>
00060 #include <pcl/ModelCoefficients.h>
00061 #include <pcl/filters/project_inliers.h>
00062 #include <pcl/surface/concave_hull.h>
00063 #include <visualization_msgs/Marker.h>
00064 
00065 #include "jsk_recognition_utils/pcl_util.h"
00066 #include "jsk_recognition_utils/random_util.h"
00067 
00068 #include <jsk_recognition_msgs/PolygonArray.h>
00069 #include "jsk_recognition_utils/sensor_model/camera_depth_sensor.h"
00070 #include "jsk_recognition_utils/types.h"
00071 #include "jsk_recognition_utils/geo/line.h"
00072 #include "jsk_recognition_utils/geo/segment.h"
00073 #include "jsk_recognition_utils/geo/polyline.h"
00074 #include "jsk_recognition_utils/geo/plane.h"
00075 #include "jsk_recognition_utils/geo/polygon.h"
00076 #include "jsk_recognition_utils/geo/convex_polygon.h"
00077 #include "jsk_recognition_utils/geo/cube.h"
00078 #include "jsk_recognition_utils/geo/cylinder.h"
00079 #include "jsk_recognition_utils/geo/grid_plane.h"
00080 
00081 // Utitlity macros
00082 inline void ROS_INFO_EIGEN_VECTOR3(const std::string& prefix,
00083                                    const Eigen::Vector3f& v) {
00084   ROS_INFO("%s: [%f, %f, %f]", prefix.c_str(), v[0], v[1], v[2]);
00085 }
00086 
00087 namespace jsk_recognition_utils
00088 {
00090   // compute quaternion from 3 unit vector
00091   // these vector should be normalized and diagonal
00093   Eigen::Quaternionf rotFrom3Axis(const Eigen::Vector3f& ex,
00094                                   const Eigen::Vector3f& ey,
00095                                   const Eigen::Vector3f& ez);
00100   template<class PointT>
00101   typename pcl::PointCloud<PointT>::Ptr verticesToPointCloud(const Vertices& v)
00102   {
00103     typename pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00104     for (size_t i = 0; i < v.size(); i++) {
00105       PointT p;
00106       // Do not use pointFromVectorToXYZ in order not to depend on
00107       // pcl_conversion_util
00108       //pointFromVectorToXYZ<Eigen::Vector3f, PointT>(v[i], p);
00109       p.x = v[i][0];
00110       p.y = v[i][1];
00111       p.z = v[i][2];
00112       cloud->points.push_back(p);
00113     }
00114     return cloud;
00115   }
00116 
00121   template<class PointT>
00122   Vertices pointCloudToVertices(const pcl::PointCloud<PointT>& cloud)
00123   {
00124     Vertices vs;
00125     for (size_t i = 0; i < cloud.points.size(); i++) {
00126       Eigen::Vector3f p(cloud.points[i].getVector3fMap());
00127       vs.push_back(p);
00128     }
00129     return vs;
00130   }
00131 
00132   // geoemtry classes
00133 
00134   std::vector<Plane::Ptr> convertToPlanes(
00135     std::vector<pcl::ModelCoefficients::Ptr>);
00136 
00137   template <class PointT>
00138   jsk_recognition_msgs::BoundingBox boundingBoxFromPointCloud(const pcl::PointCloud<PointT>& cloud)
00139   {
00140     Eigen::Vector4f minpt, maxpt;
00141     pcl::getMinMax3D<PointT>(cloud, minpt, maxpt);
00142     jsk_recognition_msgs::BoundingBox bbox;
00143     bbox.dimensions.x = std::abs(minpt[0] - maxpt[0]);
00144     bbox.dimensions.y = std::abs(minpt[1] - maxpt[1]);
00145     bbox.dimensions.z = std::abs(minpt[2] - maxpt[2]);
00146     bbox.pose.position.x = (minpt[0] + maxpt[0]) / 2.0;
00147     bbox.pose.position.y = (minpt[1] + maxpt[1]) / 2.0;
00148     bbox.pose.position.z = (minpt[2] + maxpt[2]) / 2.0;
00149     bbox.pose.orientation.w = 1.0;
00150     return bbox;
00151   }  
00152 }
00153 
00154 #endif


jsk_recognition_utils
Author(s):
autogenerated on Tue Jul 2 2019 19:40:37