shape_extraction.h
Go to the documentation of this file.
00001 #ifndef _SURFACE_PERCEPTION_SHAPE_EXTRACTION_H_
00002 #define _SURFACE_PERCEPTION_SHAPE_EXTRACTION_H_
00003 
00004 #include "geometry_msgs/Pose.h"
00005 #include "geometry_msgs/Vector3.h"
00006 #include "pcl/ModelCoefficients.h"
00007 #include "pcl/PointIndices.h"
00008 #include "pcl/point_cloud.h"
00009 #include "pcl/point_types.h"
00010 
00011 #include "surface_perception/surface.h"
00012 
00013 namespace surface_perception {
00034 bool FitBox(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& input,
00035             const pcl::PointIndicesPtr& indices,
00036             const pcl::ModelCoefficients::Ptr& model, geometry_msgs::Pose* pose,
00037             geometry_msgs::Vector3* dimensions);
00038 
00057 bool FitBoxOnSurface(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& input,
00058                      const pcl::PointIndicesPtr& indices,
00059                      const Surface& surface, geometry_msgs::Pose* pose,
00060                      geometry_msgs::Vector3* dimensions);
00061 
00084 Eigen::Matrix3f StandardizeBoxOrientation(
00085     const Eigen::Matrix3f& rotation_matrix, double x_dim, double y_dim,
00086     double* updated_x_dim, double* updated_y_dim);
00087 }  // namespace surface_perception
00088 
00089 #endif  // _SURFACE_PERCEPTION_SHAPE_EXTRACTION_


surface_perception
Author(s): Yu-Tang Peng
autogenerated on Thu Jun 6 2019 17:36:21