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 #include "object_segmentation_gui/table_transform.h"
00031
00032 namespace object_segmentation_gui {
00033
00034 TableTransform::TableTransform()
00035 {}
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045 TableTransform::~TableTransform()
00046 {}
00047
00048 void TableTransform::setParams(const sensor_msgs::CameraInfo &cam_info, float baseline, float up_direction)
00049 {
00050 cam_info_ = cam_info;
00051 baseline_ = baseline;
00052 up_direction_ = up_direction;
00053 }
00054
00055
00056
00057 tabletop_object_detector::Table TableTransform::get3DTable(float alpha,
00058 float beta,
00059 float gamma,
00060 sensor_msgs::PointCloud &table_points,
00061 std_msgs::Header table_header){
00062
00063
00064 pcl::ModelCoefficients table_coefficients =
00065 convertTo3DPlane( cam_info_, alpha, beta, gamma);
00066
00067 ROS_INFO ("Table found with %d inliers: [%f %f %f %f].",
00068 (int)table_points.points.size (),
00069 table_coefficients.values[0], table_coefficients.values[1],
00070 table_coefficients.values[2], table_coefficients.values[3]);
00071
00072 tf::Transform table_plane_trans = getPlaneTransform (table_coefficients, up_direction_);
00073 if (!transformPlanePoints( table_plane_trans, table_points)) {
00074 ROS_WARN("Table could not be computed");
00075 tabletop_object_detector::Table table;
00076 geometry_msgs::Pose table_pose;
00077 table_pose.position.x=table_pose.position.y=table_pose.position.z=table_pose.orientation.x
00078 =table_pose.orientation.y=table_pose.orientation.z=table_pose.orientation.w=0;
00079 return table;
00080 }
00081
00082 return getTable<sensor_msgs::PointCloud>(table_header, table_plane_trans, table_points);
00083 }
00084
00085
00086 pcl::ModelCoefficients TableTransform::convertTo3DPlane(const sensor_msgs::CameraInfo &camera_info,
00087 const float alpha,
00088 const float beta,
00089 const float gamma )
00090 {
00091 float fx = camera_info.P[0*4+0];
00092 float cx = camera_info.P[0*4+2];
00093 float cy = camera_info.P[1*4+2];
00094
00095 float A = alpha/baseline_;
00096 float B = beta/baseline_;
00097 float C = gamma/(baseline_ * fx) + (A*cx + B*cy)/fx;
00098
00099
00100
00101 float disp = alpha*cx + beta*cy + gamma;
00102
00103 float Z = baseline_*fx/disp;
00104 float D = C * Z;
00105 ROS_DEBUG("Apart from rounding error D should be 1 and is %f", D);
00106
00107 float NMod = sqrt(A*A+B*B+C*C);
00108
00109 A/=NMod;
00110 B/=NMod;
00111 C/=NMod;
00112 D/=NMod;
00113
00114 pcl::ModelCoefficients table_coefficients;
00115 table_coefficients.values.push_back(A);
00116 table_coefficients.values.push_back(B);
00117 table_coefficients.values.push_back(C);
00118 table_coefficients.values.push_back(D);
00119
00120 return table_coefficients;
00121 }
00122
00124 tf::Transform TableTransform::getPlaneTransform (pcl::ModelCoefficients coeffs,
00125 double up_direction)
00126 {
00127 ROS_ASSERT(coeffs.values.size() > 3);
00128 double a = coeffs.values[0], b = coeffs.values[1], c = coeffs.values[2], d = coeffs.values[3];
00129
00130 btVector3 position(a*d, b*d, c*d);
00131 btVector3 z(a, b, c);
00132
00133 ROS_DEBUG("z.dot: %0.3f", z.dot(btVector3(0,0,1)));
00134 ROS_DEBUG("in getPlaneTransform, z: %0.3f, %0.3f, %0.3f", z[0], z[1], z[2]);
00135 if ( z.dot( btVector3(0, 0, up_direction) ) < 0)
00136 {
00137 z = -1.0 * z;
00138 ROS_DEBUG("flipped z");
00139 }
00140 ROS_DEBUG("in getPlaneTransform, z: %0.3f, %0.3f, %0.3f", z[0], z[1], z[2]);
00141
00142
00143
00144 btVector3 x(1, 0, 0);
00145 if ( fabs(z.dot(x)) > 1.0 - 1.0e-4) x = btVector3(0, 1, 0);
00146 btVector3 y = z.cross(x).normalized();
00147 x = y.cross(z).normalized();
00148
00149 btMatrix3x3 rotation;
00150 rotation[0] = x;
00151 rotation[1] = y;
00152 rotation[2] = z;
00153 rotation = rotation.transpose();
00154 btQuaternion orientation;
00155 rotation.getRotation(orientation);
00156 return tf::Transform(orientation, position);
00157 }
00158
00159 bool TableTransform::transformPlanePoints ( const tf::Transform& table_plane_trans,
00160 sensor_msgs::PointCloud &table_points )
00161 {
00162
00163 tf::TransformListener listener;
00164 tf::StampedTransform table_pose_frame(table_plane_trans, table_points.header.stamp,
00165 table_points.header.frame_id, "table_frame");
00166 listener.setTransform(table_pose_frame);
00167 std::string error_msg;
00168
00169 if (!listener.canTransform("table_frame", table_points.header.frame_id,
00170 table_points.header.stamp, &error_msg))
00171 {
00172 ROS_ERROR("Cannot transform point cloud from frame %s to table frame; error %s",
00173 table_points.header.frame_id.c_str(), error_msg.c_str());
00174 return false;
00175 }
00176 try
00177 {
00178 listener.transformPointCloud("table_frame", table_points, table_points);
00179 }
00180 catch (tf::TransformException ex)
00181 {
00182 ROS_ERROR("Failed to transform point cloud from frame %s into table_frame; error %s",
00183 table_points.header.frame_id.c_str(), ex.what());
00184 return false;
00185 }
00186 table_points.header.frame_id = "table_frame";
00187 return true;
00188 }
00189
00190 template <class PointCloudType>
00191 tabletop_object_detector::Table TableTransform::getTable(std_msgs::Header cloud_header,
00192 const tf::Transform &table_plane_trans,
00193 const PointCloudType &table_points)
00194 {
00195 tabletop_object_detector::Table table;
00196
00197
00198 if (!table_points.points.empty())
00199 {
00200 table.x_min = table_points.points[0].x;
00201 table.x_max = table_points.points[0].x;
00202 table.y_min = table_points.points[0].y;
00203 table.y_max = table_points.points[0].y;
00204 }
00205 for (size_t i=1; i<table_points.points.size(); ++i)
00206 {
00207 if (table_points.points[i].x<table.x_min && table_points.points[i].x>-3.0)
00208 table.x_min = table_points.points[i].x;
00209 if (table_points.points[i].x>table.x_max && table_points.points[i].x< 3.0)
00210 table.x_max = table_points.points[i].x;
00211 if (table_points.points[i].y<table.y_min && table_points.points[i].y>-3.0)
00212 table.y_min = table_points.points[i].y;
00213 if (table_points.points[i].y>table.y_max && table_points.points[i].y< 3.0)
00214 table.y_max = table_points.points[i].y;
00215 }
00216
00217 geometry_msgs::Pose table_pose;
00218 tf::poseTFToMsg(table_plane_trans, table_pose);
00219
00220 ROS_DEBUG("Table Pose: [%f %f %f] [%f %f %f %f] ",
00221 table_pose.position.x, table_pose.position.y, table_pose.position.z,
00222 table_pose.orientation.x, table_pose.orientation.y, table_pose.orientation.z,
00223 table_pose.orientation.w);
00224
00225 table.pose.pose = table_pose;
00226 table.pose.header = cloud_header;
00227
00228 return table;
00229 }
00230
00231
00232 }
00233
00234