00001 #include <cstdio>
00002 #include <fstream>
00003 #include <ros/ros.h>
00004 #include <pcl/point_cloud.h>
00005 #include <sensor_msgs/PointCloud2.h>
00006 #include <pcl/io/pcd_io.h>
00007 #include <pcl/features/feature.h>
00008 #include <Eigen/Eigen>
00009 #include <fstream>
00010 #include <image_transport/image_transport.h>
00011 #include <image_transport/subscriber_filter.h>
00012 #include <message_filters/subscriber.h>
00013 #include <message_filters/time_synchronizer.h>
00014 #include <tf/message_filter.h>
00015 #include <tf/transform_broadcaster.h>
00016 #include <tf_conversions/tf_eigen.h>
00017
00018 #include <depth_camera.h>
00019
00020 #include <ndt_feature_reg/ndt_frame.h>
00021 #include <ndt_feature_reg/exp_ndt_frame_proc.h>
00022 #include <ndt_feature_reg/ndt_frame_viewer.h>
00023
00024 #include <opencv/cv.h>
00025 #include <opencv/highgui.h>
00026 #include <boost/shared_ptr.hpp>
00027 #if ROS_VERSION_MINIMUM(1,9,0)
00028
00029 #include <cv_bridge/cv_bridge.h>
00030 #else
00031
00032 #include <cv_bridge/CvBridge.h>
00033 #endif
00034
00035 #include <sensor_msgs/Image.h>
00036 #include <sensor_msgs/CameraInfo.h>
00037 #include <message_filters/time_synchronizer.h>
00038 #include <message_filters/sync_policies/approximate_time.h>
00039
00040 using namespace lslgeneric;
00041 using namespace ndt_feature_reg;
00042
00043 cv::Mat generateLookupTable(const pcl::PointCloud<pcl::PointXYZ> &pointcloud)
00044 {
00045 cv::Mat lookup_table(cv::Size(pointcloud.width, pointcloud.height), CV_64FC3);
00046 if (pointcloud.is_dense)
00047 {
00048
00049 }
00050 else
00051 {
00052 assert(false);
00053 }
00054 return lookup_table;
00055 }
00056
00057 void subsamplePointCloud(const pcl::PointCloud<pcl::PointXYZ> &orig, pcl::PointCloud<pcl::PointXYZ> &sub, int step)
00058 {
00059 uint32_t x = 0;
00060 while (x < orig.width)
00061 {
00062 uint32_t y = 0;
00063 while (y*step < orig.height)
00064 {
00065 sub.push_back(orig.at(x*step, y*step));
00066 y += step;
00067 }
00068 x += step;
00069 }
00070 }
00071
00072
00073
00074 class NDTFeatureRegNode
00075 {
00076 protected:
00077 ros::NodeHandle nh_;
00078
00079 message_filters::Subscriber<sensor_msgs::Image> rgb_sub_;
00080 message_filters::Subscriber<sensor_msgs::Image> depth_sub_;
00081 ros::Subscriber depth_param_sub_;
00082 message_filters::Subscriber<sensor_msgs::Image> intensity_sub_;
00083 message_filters::Subscriber<sensor_msgs::PointCloud2> points2_sub_;
00084
00085 message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> > sync_;
00086 message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2> > sync2_;
00087
00088 sensor_msgs::CvBridge _imBridge;
00089 bool visualize_;
00090
00091 tf::TransformBroadcaster tf_;
00092 tf::TransformListener tf_listener_;
00093
00094 ros::Publisher pub_points2_;
00095
00096 boost::mutex m_;
00097 lslgeneric::DepthCamera<pcl::PointXYZ> cameraparams_;
00098 bool camerasetup_;
00099 bool skip_matching_;
00100 bool estimate_di_;
00101 bool match_full_;
00102 bool match_no_association_;
00103 int support_size_;
00104 double max_var_;
00105 double current_res_;
00106 int max_nb_frames_;
00107
00108 int camera_nb_;
00109 bool set_initial_pose_;
00110 bool publish_cloud_;
00111 int subsample_step_;
00112
00113 ros::Time prev_timestamp_;
00114 ExpNDTFrameProc<pcl::PointXYZ>* proc;
00115 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> global_transform_;
00116 void TransformEigenToTF(const Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &k, tf::Transform &t)
00117 {
00118 t.setOrigin(tf::Vector3(k.matrix()(0,3), k.matrix()(1,3), k.matrix()(2,3)));
00119 t.setBasis(btMatrix3x3(k.matrix()(0,0), k.matrix()(0,1),k.matrix()(0,2),k.matrix()(1,0), k.matrix()(1,1),k.matrix()(1,2),k.matrix()(2,0), k.matrix()(2,1),k.matrix()(2,2)));
00120 };
00121
00122 void setupCamera(const sensor_msgs::CameraInfoConstPtr & camera_info)
00123 {
00124
00125 m_.lock();
00126 if(!camerasetup_) {
00127
00128 std::cout<<"seting up camera params\n";
00129 double fx, fy, cx, cy, ds=1;
00130 std::vector<double> dist(5);
00131 fx = camera_info->K[0];
00132 fy = camera_info->K[4];
00133 cx = camera_info->K[2];
00134 cy = camera_info->K[5];
00135 if(camera_info->D.size() == 5) {
00136 dist = camera_info->D;
00137 } else {
00138 dist = std::vector<double>(5,0);
00139 }
00140 std::cout<<"Params: "<<fx<<" "<<fy<<" "<<cx<<" "<<cy<<" "<<dist.size()<<std::endl;
00141 cameraparams_ = lslgeneric::DepthCamera<pcl::PointXYZ>(fx,fy,cx,cy,dist,ds,true);
00142
00143 camerasetup_ = true;
00144 }
00145 m_.unlock();
00146
00147 }
00148
00149 public:
00150
00151 NDTFeatureRegNode(ros::NodeHandle param_nh) : sync_(2), sync2_(2)
00152 {
00153 bool xyzi_data;
00154 param_nh.param("xyzi_data", xyzi_data, false);
00155
00156 if (!xyzi_data)
00157 {
00158 rgb_sub_.subscribe(nh_, "rgb", 2);
00159 depth_sub_.subscribe(nh_, "depth", 2);
00160 depth_param_sub_ = nh_.subscribe("depth_param", 1, &NDTFeatureRegNode::setupCamera, this);
00161
00162 sync_.connectInput(rgb_sub_, depth_sub_);
00163 sync_.registerCallback( boost::bind(&NDTFeatureRegNode::rgbDepthCb, this, _1, _2) );
00164 }
00165 else
00166 {
00167 intensity_sub_.subscribe(nh_, "intensity", 1);
00168 points2_sub_.subscribe(nh_, "points2", 2);
00169 sync2_.connectInput(intensity_sub_, points2_sub_);
00170 sync2_.registerCallback( boost::bind(&NDTFeatureRegNode::intensityPoints2Cb, this, _1, _2) );
00171 }
00172
00173 pub_points2_ = nh_.advertise<sensor_msgs::PointCloud2>("reg_points2", 15);
00174
00175 param_nh.param("visualize", visualize_, false);
00176
00177 param_nh.param("skip_matching", skip_matching_, false);
00178 param_nh.param("estimate_di", estimate_di_, false);
00179 param_nh.param("match_full", match_full_, false);
00180 param_nh.param("match_no_association", match_no_association_, false);
00181 param_nh.param("support_size", support_size_, 10);
00182 param_nh.param("max_var", max_var_, 0.3);
00183 param_nh.param("current_res", current_res_, 0.2);
00184 param_nh.param("max_nb_frames", max_nb_frames_, 10);
00185
00186 param_nh.param("camera_nb", camera_nb_, 1);
00187
00188 double max_inldist_xy, max_inldist_z;
00189 int nb_ransac;
00190
00191 param_nh.param("max_inldist_xy", max_inldist_xy, 0.02);
00192 param_nh.param("max_inldist_z", max_inldist_z, 0.05);
00193 param_nh.param("nb_ransac", nb_ransac, 1000);
00194
00195 proc = new ExpNDTFrameProc<pcl::PointXYZ>(nb_ransac, max_inldist_xy, max_inldist_z);
00196
00197 double detector_thresh;
00198 param_nh.param("detector_thresh", detector_thresh, 400.);
00199
00200 proc->detector = cv::FeatureDetector::create("SURF");
00201
00202 param_nh.param("img_scale", proc->img_scale, 0.25);
00203 param_nh.param("trim_factor", proc->trim_factor, 1.);
00204 param_nh.param("non_mean", proc->non_mean, false);
00205 param_nh.param("windowed_matching2", proc->pe.windowed, false);
00206 param_nh.param("max_kp_dist", proc->pe.maxDist, 10.);
00207 param_nh.param("min_kp_dist", proc->pe.minDist, 0.);
00208 param_nh.param("set_initial_pose", set_initial_pose_, false);
00209
00210 param_nh.param("publish_cloud", publish_cloud_, false);
00211 param_nh.param("subsample_step", subsample_step_, 5);
00212
00213 camerasetup_ = false;
00214 global_transform_.setIdentity();
00215 }
00216
00217 ~NDTFeatureRegNode()
00218 {
00219 delete proc;
00220 }
00221
00222 void process(cv::Mat &rgb_img, cv::Mat &depth_img, const ros::Time ¤t_timestamp)
00223 {
00224 NDTFrame<pcl::PointXYZ> *frame = new NDTFrame<pcl::PointXYZ>();
00225
00226
00227 rgb_img.copyTo(frame->img);
00228 depth_img.copyTo(frame->depth_img);
00229 frame->supportSize = support_size_;
00230 frame->maxVar = max_var_;
00231 frame->current_res = current_res_;
00232 frame->cameraParams = cameraparams_;
00233 proc->addFrameIncremental(frame, skip_matching_, estimate_di_,match_full_,match_no_association_);
00234
00235 if (visualize_)
00236 {
00237 viewKeypointMatchesFirst(proc, 10);
00238 }
00239
00240
00241 proc->trimNbFrames(max_nb_frames_);
00242
00243 global_transform_ = proc->transformVector.back();
00244 tf::Transform transform;
00245 tf::Transform global_transform;
00246 TransformEigenToTF(proc->transformVector.back(), transform);
00247 TransformEigenToTF(global_transform_, global_transform);
00248
00249
00250 tf_.sendTransform(tf::StampedTransform(transform, current_timestamp, "world", "ndt_feature_reg"));
00251 tf_.sendTransform(tf::StampedTransform(global_transform, current_timestamp, "world", "global_ndt_feature_reg"));
00252
00253 std::string gt_frame = "/camera_rgb_optical_frame";
00254 if (publish_cloud_)
00255 {
00256 pcl::PointCloud<pcl::PointXYZ> depthcloud, sub_depthcloud;
00257 cameraparams_.convertDepthImageToPointCloud(frame->depth_img,depthcloud);
00258
00259 subsamplePointCloud(depthcloud, sub_depthcloud, subsample_step_);
00260
00261 sensor_msgs::PointCloud2 pcloud;
00262 pcl::toROSMsg(sub_depthcloud,pcloud);
00263 pcloud.header.stamp = ros::Time::now();
00264 pcloud.header.frame_id = "global_ndt_feature_reg";
00265 pub_points2_.publish(pcloud);
00266 }
00267
00268 try
00269 {
00270 tf::StampedTransform gt_transform;
00271
00272 tf_listener_.waitForTransform(gt_frame, prev_timestamp_,
00273 gt_frame, current_timestamp,
00274 "/world", ros::Duration(2.0));
00275
00276 tf_listener_.lookupTransform(gt_frame, prev_timestamp_,
00277 gt_frame, current_timestamp,
00278 "/world", gt_transform);
00279
00280 tf_.sendTransform(tf::StampedTransform(gt_transform, current_timestamp, "world", "gt_reg"));
00281
00282 if (set_initial_pose_)
00283 {
00284 tf::StampedTransform glb_gt_transform;
00285 tf_listener_.lookupTransform("/world", gt_frame, current_timestamp, glb_gt_transform);
00286 TransformTFToEigen(glb_gt_transform, global_transform_);
00287 set_initial_pose_ = false;
00288 }
00289
00290 prev_timestamp_ = current_timestamp;
00291 }
00292 catch ( tf::TransformException & ex )
00293 {
00294 ROS_ERROR( "%s",
00295 ex.what() );
00296 }
00297
00298 }
00299
00300 void intensityPoints2Cb(const sensor_msgs::ImageConstPtr& msg_img, const sensor_msgs::PointCloud2::ConstPtr& msg_pts)
00301 {
00302 m_.lock();
00303
00304 ROS_INFO("Got intensity and points2 pair...");
00305 cv::Mat intensity(_imBridge.imgMsgToCv(msg_img, "mono8"));
00306 pcl::PointCloud<pcl::PointXYZ> pc;
00307 pcl::fromROSMsg (*msg_pts, pc);
00308
00309
00310
00311 if (!camerasetup_)
00312 {
00313 cameraparams_.setLookupTable(generateLookupTable(pc));
00314 camerasetup_ = true;
00315 }
00316 m_.unlock();
00317 }
00318
00319 void rgbDepthCb(const sensor_msgs::ImageConstPtr& msg_rgb, const sensor_msgs::ImageConstPtr& msg_depth)
00320 {
00321 m_.lock();
00322
00323 cv::Mat rgb_img(_imBridge.imgMsgToCv(msg_rgb, "bgr8"));
00324 cv::Mat depth_img(_imBridge.imgMsgToCv(msg_depth));
00325
00326 if (camerasetup_)
00327 {
00328 process(rgb_img, depth_img, msg_rgb->header.stamp);
00329 }
00330 m_.unlock();
00331 }
00332
00333 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00334
00335 };
00336
00337 int main(int argc, char **argv)
00338 {
00339 ros::init(argc, argv, "ndt_feature_reg_node");
00340
00341 ros::NodeHandle param_nh ("~");
00342
00343 NDTFeatureRegNode n(param_nh);
00344 ros::spin();
00345
00346 return 0;
00347 }