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 #ifndef PLANE_TRANSFORM
00034 #define PLANE_TRANSFORM
00035
00036 #include <sensor_msgs/CameraInfo.h>
00037 #include <sensor_msgs/PointCloud.h>
00038
00039
00040 #include "fast_plane_detection/Plane.h"
00041
00042 #include <tf/transform_listener.h>
00043
00044 namespace fast_plane_detection {
00045
00046 typedef geometry_msgs::Point32 Point;
00047
00048 class PlaneTransform {
00049
00050 public:
00051 PlaneTransform(const sensor_msgs::CameraInfo &camera_info,
00052 float baseline, float up_direction);
00053
00054 ~PlaneTransform();
00055
00056 void setParameters( float alpha,
00057 float beta,
00058 float d,
00059 int min_x, int max_x,
00060 int min_y, int max_y,
00061 std_msgs::Header header);
00062
00063 bool getPlane( fast_plane_detection::Plane &plane );
00064
00065 private:
00066
00067 std::vector<double> convertTo3DPlane(const sensor_msgs::CameraInfo &camera_info,
00068 float alpha,
00069 float beta,
00070 float d );
00071
00072 tf::Transform getPlaneTransform (const std::vector<double> &coeffs,
00073
00074 double up_direction);
00075
00076 bool transformPlanePoints ( const tf::Transform& plane_trans,
00077 sensor_msgs::PointCloud &plane_limits );
00078
00079 fast_plane_detection::Plane
00080 constructPlaneMsg(const sensor_msgs::PointCloud &plane_limits,
00081 const std::vector<double> &coeffs,
00082 const tf::Transform &plane_trans);
00083
00084 void get3DTableLimits(sensor_msgs::PointCloud &plane_limits);
00085
00086 void get3DPlanePoint( int u, int v, Point &p);
00087
00088 sensor_msgs::CameraInfo camera_info_;
00089
00090 float baseline_;
00091 float up_direction_;
00092
00093 float alpha_, beta_, d_;
00094
00095 int min_x_, max_x_;
00096 int min_y_, max_y_;
00097
00098 std_msgs::Header header_;
00099
00100 tf::TransformListener listener;
00101
00102 };
00103
00104 }
00105
00106 #endif