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 #include <ros/ros.h>
00034 #include <std_msgs/String.h>
00035
00036 #include <sensor_msgs/CameraInfo.h>
00037 #include <stereo_msgs/DisparityImage.h>
00038
00039 #include <fast_plane_detection/Plane.h>
00040
00041 #include <visualization_msgs/Marker.h>
00042
00043 #include <tf/transform_listener.h>
00044
00045 #include "fast_plane_detector/plane_detection.h"
00046 #include "fast_plane_detector/plane_transform.h"
00047
00048 #include "fast_plane_detector/timercpu.h"
00049 #include "fast_plane_detector/utils.h"
00050
00051 #include <fast_plane_detection/SetPosition.h>
00052 #include <fast_plane_detection/SlavePoint.h>
00053
00054
00055 namespace fast_plane_detection {
00056
00057 class FastRegionPlaneDetector {
00058
00059 private:
00060
00061 bool maskDisparityImage(
00062 const stereo_msgs::DisparityImage::ConstPtr& disparity,
00063 const sensor_msgs::CameraInfo::ConstPtr& camera_info,
00064 const stereo_msgs::DisparityImage::Ptr &masked_disparity);
00066 ros::NodeHandle root_nh_;
00068 ros::NodeHandle priv_nh_;
00069
00071 ros::Subscriber camera_info_sub_;
00072 std::string camera_info_topic_;
00073
00075 ros::Subscriber disparity_image_sub_;
00076 std::string disparity_image_topic_;
00077
00079 int buffer_size_;
00080
00082 stereo_msgs::DisparityImage::ConstPtr disparity_image_;
00083
00085 stereo_msgs::DisparityImage disparity_masked_;
00086 stereo_msgs::DisparityImage::Ptr disparity_masked_ptr;
00087
00089 sensor_msgs::CameraInfo::ConstPtr camera_info_;
00090
00092 ros::Publisher plane_marker_pub_;
00093
00095 ros::Publisher pos_marker_pub_;
00096
00098 ros::Publisher plane_msg_pub_;
00099
00101 ros::Publisher disparity_image_pub_;
00102
00103 tf::TransformListener listener_;
00104
00105 tf::TransformListener listener_check_;
00106 tf::StampedTransform transform_check_;
00107
00108 tf::TransformListener listener_check2_;
00109 tf::StampedTransform transform_check2_;
00110
00112 PlaneDetection* plane_detect_;
00113
00115 bool find_table_;
00116
00118 PlaneTransform* plane_transform_;
00119
00121 double up_direction_;
00122
00124 int inlier_threshold_;
00125 int number_inliers_;
00126 double percentage_inliers_;
00127 float mean_error_;
00128
00129
00130 ros::ServiceServer srv_position_;
00131 double X_;
00132 double Y_;
00133 double Z_;
00134 bool manual_;
00135 bool in_contact_;
00136
00137 ros::Subscriber sub_position_;
00138
00140 geometry_msgs::Vector3Stamped point_;
00141 int region_width_;
00142 int region_height_;
00143
00144 int marker_id_;
00145 int marker2_id_;
00146
00147
00148 std::string source_frame_;
00149 std::string camera_frame_;
00150
00151
00152 std_msgs::ColorRGBA green_;
00153 std_msgs::ColorRGBA red_;
00154
00155 public:
00156
00157 FastRegionPlaneDetector(int buffer_size);
00158 ~FastRegionPlaneDetector();
00159
00160
00161
00163 void planeCallback(
00164 const stereo_msgs::DisparityImage::ConstPtr& disparity_image);
00165
00166
00167 bool setPosition(fast_plane_detection::SetPosition::Request& req,
00168 fast_plane_detection::SetPosition::Response& resp);
00169
00170
00171 void Pr2Callback(const fast_plane_detection::SlavePoint msg_pose);
00172
00173
00174
00176 Plane plane_;
00177
00178 };
00179
00180 FastRegionPlaneDetector::FastRegionPlaneDetector(int buffer_size) :
00181 root_nh_(""), priv_nh_("~"), X_(0), Y_(0), Z_(1), number_inliers_(0), percentage_inliers_(0),
00182 buffer_size_(buffer_size), region_width_(10), region_height_(40), manual_(false),
00183 marker_id_(354345)
00184 , marker2_id_(154345)
00185 , source_frame_("/torso_lift_link")
00186 , camera_frame_("/narrow_stereo_optical_frame")
00187 {
00188
00189 green_.r = 0, green_.g = 0.8, green_.b = 0, green_.a = 1;
00190 red_.r = 1, red_.g = 0, red_.b = 0, red_.a = 1;
00191
00192
00193 priv_nh_.param<std::string> ("camera_info_topic", camera_info_topic_,
00194 "/narrow_stereo_textured/left/camera_info");
00195 priv_nh_.param<std::string> ("disparity_image_topic",
00196 disparity_image_topic_, "/narrow_stereo_textured/disparity");
00197 priv_nh_.param<bool> ("find_table", find_table_, false);
00198 priv_nh_.param<double> ("up_direction", up_direction_, -1.0f);
00199 priv_nh_.param<int> ("inlier_threshold", inlier_threshold_, 300);
00200
00201
00202
00203 while (!camera_info_ || !disparity_image_) {
00204 if (!camera_info_) {
00205 ROS_INFO_STREAM(" Waiting for message on topic "
00206 << camera_info_topic_);
00207 camera_info_ = ros::topic::waitForMessage<sensor_msgs::CameraInfo>(
00208 camera_info_topic_, root_nh_, ros::Duration(0.5));
00209 }
00210
00211 if (!disparity_image_) {
00212 ROS_INFO_STREAM(" Waiting for message on topic "
00213 << disparity_image_topic_);
00214 disparity_image_ = ros::topic::waitForMessage<
00215 stereo_msgs::DisparityImage>(disparity_image_topic_,
00216 root_nh_, ros::Duration(1.0));
00217 }
00218 }
00219
00220
00221 disparity_masked_.header = disparity_image_->header;
00222 disparity_masked_.image.header = disparity_image_->image.header;
00223 disparity_masked_.image.height = disparity_image_->image.height;
00224 disparity_masked_.image.width = disparity_image_->image.width;
00225 disparity_masked_.image.encoding = disparity_image_->image.encoding;
00226 disparity_masked_.image.is_bigendian = disparity_image_->image.is_bigendian;
00227
00228
00229 disparity_masked_.image.step = disparity_image_->image.step;
00230 size_t size = disparity_masked_.image.step * disparity_masked_.image.height;
00231 disparity_masked_.image.data.resize(size, 0);
00232
00233 disparity_masked_.f = disparity_image_->f;
00234 disparity_masked_.T = disparity_image_->T;
00235 disparity_masked_.min_disparity = disparity_image_->min_disparity;
00236 disparity_masked_.max_disparity = disparity_image_->max_disparity;
00237 disparity_masked_.delta_d = disparity_image_->delta_d;
00238
00239
00240
00241
00242
00243
00244 float drange = disparity_image_->max_disparity
00245 - disparity_image_->min_disparity;
00246 int w = disparity_image_->image.width;
00247 int h = disparity_image_->image.height;
00248
00249 plane_detect_ = new PlaneDetection((int) drange, w, h, find_table_,
00250 disparity_image_->image.header);
00251
00252 plane_transform_ = new PlaneTransform(*camera_info_, disparity_image_->T,
00253 up_direction_);
00254
00255
00256 std::string topic_disp = root_nh_.resolveName("disparity_in");
00257 disparity_image_sub_ = root_nh_.subscribe(topic_disp, buffer_size_,
00258 &FastRegionPlaneDetector::planeCallback, this);
00259
00260
00261 plane_marker_pub_ = root_nh_.advertise<visualization_msgs::Marker> (
00262 "region_plane_markers", 1);
00263
00264
00265 pos_marker_pub_ = root_nh_.advertise<visualization_msgs::Marker> (
00266 "slave_pos_marker", 1);
00267
00268
00269 plane_msg_pub_ = root_nh_.advertise<Plane> ("region_plane_msg", 1);
00270
00271
00272 std::string topic = root_nh_.resolveName(
00273 "/plane_detection/masked_disparity");
00274 disparity_image_pub_ = root_nh_.advertise<stereo_msgs::DisparityImage> (
00275 topic, 1);
00276
00277
00278 srv_position_ = root_nh_.advertiseService("set_position", &FastRegionPlaneDetector::setPosition, this);
00279
00280
00281 sub_position_ = root_nh_.subscribe("/bilateral_teleop/slave_point", 1, &FastRegionPlaneDetector::Pr2Callback,this);
00282
00283 }
00284
00285 FastRegionPlaneDetector::~FastRegionPlaneDetector() {
00286 delete plane_detect_;
00287 delete plane_transform_;
00288 }
00289
00290 void FastRegionPlaneDetector::planeCallback(
00291 const stereo_msgs::DisparityImage::ConstPtr& disparity_image) {
00292 ROS_INFO("-----------------");
00293 TimerCPU timer(2800);
00294
00295 stereo_msgs::DisparityImage::Ptr disparity_masked_ptr = boost::make_shared<
00296 stereo_msgs::DisparityImage>(disparity_masked_);
00297
00298
00299 if (!maskDisparityImage(disparity_image, camera_info_, disparity_masked_ptr)) {
00300 ROS_WARN("Could not project input point to disparity image");
00301 plane_.result = Plane::OTHER_ERROR;
00302 return;
00303 }
00304
00305 disparity_image_pub_.publish(*disparity_masked_ptr);
00306 plane_detect_->Update(disparity_masked_ptr);
00307
00308 float alpha, beta, d;
00309 int min_x, max_x, min_y, max_y;
00310 plane_detect_->GetPlaneParameters(alpha, beta, d, min_x, max_x, min_y,
00311 max_y);
00312
00313 sensor_msgs::Image labels;
00314 plane_detect_->GetLabels(labels);
00315
00316
00317
00318 int sum = 0;
00319 for (unsigned int i = 0; i < labels.height; ++i)
00320 for (unsigned int j = 0; j < labels.width; ++j) {
00321 int adr = i * labels.width + j;
00322 sum += (labels.data[adr]) / 255;
00323 }
00324 number_inliers_ = sum;
00325
00326
00327
00328
00329 plane_detect_->GetMeanSquaredError(mean_error_);
00330
00331
00332 inlier_threshold_ = (region_width_ * region_height_) / 3;
00333 percentage_inliers_ = 100*number_inliers_/(region_width_ * region_height_);
00334
00335 plane_transform_->setParameters(alpha, beta, d, min_x, max_x, min_y, max_y,
00336 disparity_image->header);
00337
00338 if (!plane_transform_->getPlane(plane_)) {
00339 ROS_WARN("No Plane found");
00340 plane_.result = Plane::NO_PLANE;
00341 plane_msg_pub_.publish(plane_);
00342 return;
00343 } else {
00344
00345
00346 try {
00347 listener_check2_.lookupTransform(source_frame_,camera_frame_, ros::Time(0), transform_check2_);
00348 } catch (tf::TransformException ex) {
00349 ROS_ERROR("%s", ex.what());
00350 }
00351
00352 btVector3 point1(plane_.pose.pose.position.x, plane_.pose.pose.position.y, plane_.pose.pose.position.z);
00353 point1 = transform_check2_.getBasis() * point1 + transform_check2_.getOrigin();
00354 geometry_msgs::PointStamped plane_point;
00355 plane_point.header.frame_id = "torso_lift_link";
00356 plane_point.header.stamp = ros::Time::now();
00357 plane_point.point.x = point1.x();
00358 plane_point.point.y = point1.y();
00359 plane_point.point.z = point1.z();
00360 plane_.plane_point = plane_point;
00361
00362 btVector3 point2(plane_.normal.vector.x, plane_.normal.vector.y, plane_.normal.vector.z);
00363 point2 = transform_check2_.getBasis() * point2;
00364 ROS_INFO("Normal of plane: %f %f %f", plane_.normal.vector.x, plane_.normal.vector.y, plane_.normal.vector.z);
00365 geometry_msgs::Vector3Stamped plane_normal;
00366 plane_normal.header.frame_id = "torso_lift_link";
00367 plane_normal.header.stamp = ros::Time::now();
00368 plane_normal.vector.x = point2.x();
00369 plane_normal.vector.y = point2.y();
00370 plane_normal.vector.z = point2.z();
00371 plane_.normal = plane_normal;
00372
00373 plane_.plane_d = -1*(point1.x()*point2.x() + point1.y()*point2.y() + point1.z()*point2.z());
00374
00375 geometry_msgs::PointStamped slave_point;
00376 slave_point.header.frame_id = "torso_lift_link";
00377 slave_point.header.stamp = ros::Time::now();
00378 slave_point.point.x = X_;
00379 slave_point.point.y = Y_;
00380 slave_point.point.z = Z_;
00381 plane_.slave_point = slave_point;
00382
00383 if(number_inliers_<inlier_threshold_){
00384 ROS_WARN("Percentage of inliers is only %f", percentage_inliers_);
00385 plane_.result = Plane::FEW_INLIERS;
00386 }
00387 else{
00388 ROS_INFO("Percentage of inliers is %f", percentage_inliers_);
00389 plane_.result = Plane::SUCCESS;
00390 }
00391 ROS_INFO("Mean squared error is %f", mean_error_);
00392 plane_.percentage_inliers = percentage_inliers_;
00393 plane_.error = mean_error_;
00394 plane_msg_pub_.publish(plane_);
00395
00396 visualization_msgs::Marker delete_marker;
00397 delete_marker.header.stamp = ros::Time::now();
00398 delete_marker.header.frame_id = disparity_image->header.frame_id;
00399 delete_marker.id = marker_id_;
00400 delete_marker.action = visualization_msgs::Marker::DELETE;
00401 delete_marker.ns = "tabletop_node";
00402 plane_marker_pub_.publish(delete_marker);
00403
00404 visualization_msgs::Marker planeMarker = getPlaneMarker(
00405 plane_.top_left, plane_.top_right, plane_.bottom_left,
00406 plane_.bottom_right);
00407 planeMarker.header = disparity_image->header;
00408 planeMarker.pose = plane_.pose.pose;
00409 planeMarker.ns = "tabletop_node";
00410 planeMarker.id = marker_id_;
00411 if(in_contact_)
00412 planeMarker.color = red_;
00413 else
00414 planeMarker.color = green_;
00415 planeMarker.scale.x = 0.002;
00416 plane_marker_pub_.publish(planeMarker);
00417
00418 }
00419
00420
00421
00422
00423 }
00424
00425 bool FastRegionPlaneDetector::maskDisparityImage(
00426 const stereo_msgs::DisparityImage::ConstPtr& disparity,
00427 const sensor_msgs::CameraInfo::ConstPtr& camera_info,
00428 const stereo_msgs::DisparityImage::Ptr &masked_disparity)
00429
00430 {
00431
00432 try {
00433 listener_check_.lookupTransform(camera_frame_, source_frame_, ros::Time(0), transform_check_);
00434 } catch (tf::TransformException ex) {
00435 ROS_ERROR("%s", ex.what());
00436 }
00437
00438 btVector3 point(X_,Y_,Z_);
00439
00440 point = transform_check_ * point;
00441
00443 visualization_msgs::Marker delete_posMarker;
00444 delete_posMarker.header.stamp = ros::Time::now();
00445 delete_posMarker.header.frame_id = camera_frame_;
00446 delete_posMarker.id = marker2_id_;
00447 delete_posMarker.action = visualization_msgs::Marker::DELETE;
00448 delete_posMarker.ns = "tabletop_node";
00449 pos_marker_pub_.publish(delete_posMarker);
00450
00451 visualization_msgs::Marker posMarker;
00452 posMarker.header.frame_id = camera_frame_;
00453 posMarker.header.stamp = ros::Time::now();
00454 posMarker.ns = "tabletop_node";
00455 posMarker.id = marker2_id_;
00456 posMarker.type = visualization_msgs::Marker::SPHERE;
00457
00458
00459 posMarker.pose.position.x = point.x();
00460 posMarker.pose.position.y = point.y();
00461 posMarker.pose.position.z = point.z();
00462
00463 posMarker.scale.x = 0.01;
00464 posMarker.scale.y = 0.01;
00465 posMarker.scale.z = 0.01;
00466
00467 if(in_contact_)
00468 posMarker.color = red_;
00469 else
00470 posMarker.color = green_;
00471 pos_marker_pub_.publish(posMarker);
00472
00473
00474
00475 float f = disparity->f;
00476 float T = disparity->T;
00477
00478 float fx = camera_info->P[0 * 4 + 0];
00479 float fy = camera_info->P[1 * 4 + 1];
00480 float cx = camera_info->P[0 * 4 + 2];
00481 float cy = camera_info->P[1 * 4 + 2];
00482
00483
00484 int u = point.x() / point.z() * fx + cx;
00485 int v = point.y() / point.z() * fy + cy;
00486
00487 int d = (f * T) / point.z();
00488
00489 ROS_INFO("3D point: (%f, %f, %f) -> Pixel position (%d, %d) ",X_, Y_,Z_, u, v);
00490
00491 float *dimd_in = (float*) &(disparity->image.data[0]);
00492 float *dimd_out = (float*) &(masked_disparity->image.data[0]);
00493
00494 for (int y = 0; y < (int) masked_disparity->image.height; y++) {
00495 for (int x = 0; x < (int) masked_disparity->image.width; x++) {
00496 int adr = y * masked_disparity->image.width + x;
00497 if (x > u - region_width_ / 2 && x < u + region_width_ / 2 && y > v
00498 - region_height_ / 2 && y < v + region_height_ / 2) {
00499 dimd_out[adr] = dimd_in[adr];
00500 } else
00501 dimd_out[adr] = -1.0f;
00502 }
00503 }
00504
00505 return true;
00506 }
00507
00509 bool FastRegionPlaneDetector::setPosition(
00510 fast_plane_detection::SetPosition::Request& req,
00511 fast_plane_detection::SetPosition::Response& resp) {
00512 if (req.transform){
00513 X_ = req.x;
00514 Y_ = req.y;
00515 Z_ = req.z;
00516 }
00517 region_width_ = req.width;
00518 region_height_ = req.height;
00519 manual_ = req.transform;
00520 ROS_INFO("Fast Plane Detector: Position changed");
00521
00522 resp.x = X_;
00523 resp.y = Y_;
00524 resp.z = Z_;
00525 resp.transform = manual_;
00526 resp.width = region_width_;
00527 resp.height = region_height_;
00528 return true;
00529 }
00530
00532 void FastRegionPlaneDetector::Pr2Callback(const fast_plane_detection::SlavePoint msg_pose)
00533 {
00534 if (!manual_){
00535 X_ = msg_pose.end_effector.x;
00536 Y_ = msg_pose.end_effector.y;
00537 Z_ = msg_pose.end_effector.z;
00538 }
00539 in_contact_ = msg_pose.contact;
00540
00541
00542 }
00543
00544 }
00545
00546 int main(int argc, char **argv) {
00547 ros::init(argc, argv, "fast_plane_detection_node");
00548
00550 int buffer_size_ = 1;
00551 fast_plane_detection::FastRegionPlaneDetector node_(buffer_size_);
00552 ros::spin();
00553
00554 return 0;
00555 }