Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_RECOGNITION_UTILS_GEO_UTIL_H_
00037 #define JSK_RECOGNITION_UTILS_GEO_UTIL_H_
00038
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
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/plane.h"
00074 #include "jsk_recognition_utils/geo/polygon.h"
00075 #include "jsk_recognition_utils/geo/convex_polygon.h"
00076 #include "jsk_recognition_utils/geo/cube.h"
00077 #include "jsk_recognition_utils/geo/cylinder.h"
00078 #include "jsk_recognition_utils/geo/grid_plane.h"
00079
00080
00081 inline void ROS_INFO_EIGEN_VECTOR3(const std::string& prefix,
00082 const Eigen::Vector3f& v) {
00083 ROS_INFO("%s: [%f, %f, %f]", prefix.c_str(), v[0], v[1], v[2]);
00084 }
00085
00086 namespace jsk_recognition_utils
00087 {
00089
00090
00092 Eigen::Quaternionf rotFrom3Axis(const Eigen::Vector3f& ex,
00093 const Eigen::Vector3f& ey,
00094 const Eigen::Vector3f& ez);
00099 template<class PointT>
00100 typename pcl::PointCloud<PointT>::Ptr verticesToPointCloud(const Vertices& v)
00101 {
00102 typename pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00103 for (size_t i = 0; i < v.size(); i++) {
00104 PointT p;
00105
00106
00107
00108 p.x = v[i][0];
00109 p.y = v[i][1];
00110 p.z = v[i][2];
00111 cloud->points.push_back(p);
00112 }
00113 return cloud;
00114 }
00115
00120 template<class PointT>
00121 Vertices pointCloudToVertices(const pcl::PointCloud<PointT>& cloud)
00122 {
00123 Vertices vs;
00124 for (size_t i = 0; i < cloud.points.size(); i++) {
00125 Eigen::Vector3f p(cloud.points[i].getVector3fMap());
00126 vs.push_back(p);
00127 }
00128 return vs;
00129 }
00130
00131
00132
00133 std::vector<Plane::Ptr> convertToPlanes(
00134 std::vector<pcl::ModelCoefficients::Ptr>);
00135
00136 template <class PointT>
00137 jsk_recognition_msgs::BoundingBox boundingBoxFromPointCloud(const pcl::PointCloud<PointT>& cloud)
00138 {
00139 Eigen::Vector4f minpt, maxpt;
00140 pcl::getMinMax3D<PointT>(cloud, minpt, maxpt);
00141 jsk_recognition_msgs::BoundingBox bbox;
00142 bbox.dimensions.x = std::abs(minpt[0] - maxpt[0]);
00143 bbox.dimensions.y = std::abs(minpt[1] - maxpt[1]);
00144 bbox.dimensions.z = std::abs(minpt[2] - maxpt[2]);
00145 bbox.pose.position.x = (minpt[0] + maxpt[0]) / 2.0;
00146 bbox.pose.position.y = (minpt[1] + maxpt[1]) / 2.0;
00147 bbox.pose.position.z = (minpt[2] + maxpt[2]) / 2.0;
00148 bbox.pose.orientation.w = 1.0;
00149 return bbox;
00150 }
00151 }
00152
00153 #endif