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 #ifndef TABLE_TRANSFORM
00031 #define TABLE_TRANSFORM
00032
00033 #include <sensor_msgs/Image.h>
00034 #include <sensor_msgs/CameraInfo.h>
00035 #include <sensor_msgs/PointCloud.h>
00036
00037 #include "pcl/ModelCoefficients.h"
00038 #include "tabletop_object_detector/Table.h"
00039
00040 #include <tf/transform_listener.h>
00041
00042 namespace object_segmentation_gui {
00043
00044 class TableTransform
00045 {
00046 public:
00047
00048 TableTransform();
00049 ~TableTransform();
00050
00051 void setParams(const sensor_msgs::CameraInfo &cam_info, float baseline, float up_direction);
00052
00053 tabletop_object_detector::Table get3DTable( float alpha, float beta, float gamma,
00054 sensor_msgs::PointCloud &table_points,
00055 std_msgs::Header table_header);
00056
00057 protected:
00058
00059 private:
00060
00061 pcl::ModelCoefficients convertTo3DPlane(const sensor_msgs::CameraInfo &camera_info,
00062 const float alpha, const float beta, const float gamma );
00063
00064 tf::Transform getPlaneTransform (pcl::ModelCoefficients coeffs, double up_direction);
00065
00066 bool transformPlanePoints ( const tf::Transform& table_plane_trans,
00067 sensor_msgs::PointCloud &table_points );
00068
00069 template <class PointCloudType>
00070 tabletop_object_detector::Table getTable(std_msgs::Header cloud_header,
00071 const tf::Transform &table_plane_trans,
00072 const PointCloudType &table_points);
00073
00074 sensor_msgs::CameraInfo cam_info_;
00075
00076 float baseline_;
00077 float up_direction_;
00078
00080 tf::TransformListener listener_;
00081 };
00082 }
00083
00084 #endif // TABLE_TRANSFORM