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
00034
00035
00036
00037
00038
00039
00040
00041 #include <ros/ros.h>
00042 #include <visualization_msgs/Marker.h>
00043 #include <visualization_msgs/MarkerArray.h>
00044 #include <geometry_msgs/Point.h>
00045
00046 #include <vslam_system/vslam.h>
00047 #include <posest/pe3d.h>
00048 #include <sba/sba.h>
00049 #include <sba/sba_file_io.h>
00050 #include <frame_common/frame.h>
00051 #include <boost/shared_ptr.hpp>
00052 #include <fstream>
00053 #include <dirent.h>
00054 #include <fnmatch.h>
00055 #include <time.h>
00056 #include <opencv/highgui.h>
00057 #include <rosbag/bag.h>
00058 #include <rosbag/view.h>
00059 #include <sensor_msgs/CameraInfo.h>
00060 #include <stereo_msgs/DisparityImage.h>
00061 #include <sensor_msgs/Image.h>
00062 #include <cv_bridge/CvBridge.h>
00063
00064 using namespace std;
00065 using namespace sba;
00066 using namespace frame_common;
00067 using namespace Eigen;
00068 using namespace vslam;
00069 using namespace pcl;
00070
00071
00072 #define VISMATCH
00073
00074
00075 class VisBundler
00076 {
00077 public:
00078 VisBundler( const string& bag_filename, const string& vocabulary_tree_filename,
00079 const string& voc_weights_filename, cv::DescriptorExtractor* descriptor_extractor );
00080 ~VisBundler();
00081
00082 bool step();
00083 void spin();
00084 protected:
00085 void publishRegisteredPointclouds( ) const;
00086 void drawgraph( int dec ) const;
00087
00088
00089 ros::NodeHandle node_handle_;
00090 vslam::VslamSystem vslam_;
00091 rosbag::Bag bag_;
00092 rosbag::View view_;
00093 rosbag::View::iterator message_iterator_;
00094 ros::Publisher pt_pub_;
00095 ros::Publisher cam_pub_;
00096 ros::Publisher pc_pub_;
00097 };
00098
00099 VisBundler::VisBundler( const string& bag_filename, const string& vocabulary_tree_filename,
00100 const string& vocabulary_weights_filename, cv::DescriptorExtractor* descriptor_extractor )
00101 : node_handle_("~")
00102 , vslam_( vocabulary_tree_filename, vocabulary_weights_filename )
00103 , bag_( bag_filename )
00104 , view_( bag_ )
00105 , message_iterator_( view_.begin() )
00106 , pt_pub_( node_handle_.advertise<visualization_msgs::Marker>("points", 0) )
00107 , cam_pub_( node_handle_.advertise<visualization_msgs::Marker>("cameras", 0) )
00108 , pc_pub_( node_handle_.advertise<sensor_msgs::PointCloud2>("pointcloud", 1) )
00109 {
00110 vslam_.frame_processor_.setFrameDescriptor( descriptor_extractor );
00111 vslam_.setPointcloudProc(boost::shared_ptr<frame_common::PointcloudProc>(new frame_common::PointcloudProc()));
00112 vslam_.doPointPlane = false;
00113
00114
00115 vslam_.setKeyDist(0.01);
00116 vslam_.setKeyAngle(0.05);
00117 vslam_.setKeyInliers(200);
00118 vslam_.setHuber(40.0);
00119 vslam_.vo_.pose_estimator_->wy = 128;
00120 vslam_.vo_.pose_estimator_->wx = 128;
00121 vslam_.vo_.pose_estimator_->numRansac = 10000;
00122 vslam_.vo_.sba.verbose = false;
00123 vslam_.sba_.verbose = false;
00124
00125 srand(time(0));
00126
00127 #ifdef VISMATCH
00128 cv::namedWindow("VO tracks",0);
00129 cv::namedWindow("color image");
00130 #endif
00131 }
00132
00133 VisBundler::~VisBundler()
00134 {
00135 }
00136
00137 void VisBundler::publishRegisteredPointclouds( ) const
00138 {
00139 pcl::PointCloud<pcl::PointXYZRGB> cloud;
00140 pcl::PointCloud<pcl::PointXYZRGB> registered_cloud;
00141
00142 for(size_t i=0; i < vslam_.vo_.frames.size(); i++)
00143 {
00144
00145 if (vslam_.vo_.sba.nodes.size() < i)
00146 break;
00147 if (vslam_.vo_.frames[i].dense_pointcloud.points.size() <= 0)
00148 continue;
00149 Eigen::Quaterniond rot = vslam_.vo_.sba.nodes[i].qrot;
00150 Eigen::Vector3d trans = vslam_.vo_.sba.nodes[i].trans.head<3>();
00151
00152 transformPointCloud<PointXYZRGB>(vslam_.vo_.frames[i].dense_pointcloud, cloud, Vector3f(0,0,0), rot.cast<float>());
00153 transformPointCloud<PointXYZRGB>(cloud, cloud, trans.cast<float>(), Quaternionf(1, 0, 0, 0));
00154
00155 Quaternionf qr = Quaternionf(.5, 0, 0, .5).normalized()*Quaternionf(.5, -.5, .5, -0.5).normalized();
00156 transformPointCloud<PointXYZRGB>(cloud, cloud, Vector3f(0,0,0), qr);
00157
00158 registered_cloud.header = vslam_.vo_.frames[i].dense_pointcloud.header;
00159 registered_cloud += cloud;
00160 }
00161
00162 sensor_msgs::PointCloud2 cloud_out;
00163 pcl::toROSMsg (registered_cloud, cloud_out);
00164 cloud_out.header.frame_id = "/pgraph";
00165 pc_pub_.publish (cloud_out);
00166 }
00167
00168
00169
00170
00171 void VisBundler::drawgraph( int dec ) const
00172 {
00173 visualization_msgs::Marker cammark, ptmark, cstmark;
00174 cammark.header.frame_id = "/pgraph";
00175 cammark.header.stamp = ros::Time();
00176 cammark.ns = "pgraph";
00177 cammark.id = 0;
00178 cammark.action = visualization_msgs::Marker::ADD;
00179 cammark.pose.position.x = 0;
00180 cammark.pose.position.y = 0;
00181 cammark.pose.position.z = 0;
00182 cammark.pose.orientation.x = 0.0;
00183 cammark.pose.orientation.y = 0.0;
00184 cammark.pose.orientation.z = 0.0;
00185 cammark.pose.orientation.w = 1.0;
00186 cammark.scale.x = 0.02;
00187 cammark.scale.y = 0.02;
00188 cammark.scale.z = 0.02;
00189 cammark.color.r = 0.0f;
00190 cammark.color.g = 1.0f;
00191 cammark.color.b = 1.0f;
00192 cammark.color.a = 1.0f;
00193 cammark.lifetime = ros::Duration();
00194 cammark.type = visualization_msgs::Marker::LINE_LIST;
00195
00196 ptmark = cammark;
00197 ptmark.color.r = 1.0f;
00198 ptmark.color.g = 0.0f;
00199 ptmark.color.b = 0.0f;
00200 ptmark.color.a = 0.5f;
00201 ptmark.scale.x = 0.01;
00202 ptmark.scale.y = 0.01;
00203 ptmark.scale.z = 0.01;
00204 ptmark.type = visualization_msgs::Marker::POINTS;
00205
00206 cstmark = cammark;
00207 cstmark.color.r = 1.0f;
00208 cstmark.color.g = 1.0f;
00209 cstmark.color.b = 0.0f;
00210 cstmark.color.a = 1.0f;
00211 cstmark.scale.x = 0.03;
00212 cstmark.scale.y = 0.1;
00213 cstmark.scale.z = 0.1;
00214 cstmark.type = visualization_msgs::Marker::LINE_LIST;
00215
00216
00217
00218 int npts = vslam_.vo_.sba.tracks.size();
00219
00220
00221 if (npts <= 0) return;
00222
00223
00224 ptmark.points.resize(npts/dec+1);
00225 for (int i=0, ii=0; i<npts; i+=dec, ii++)
00226 {
00227 const Vector4d &pt = vslam_.vo_.sba.tracks[i].point;
00228 ptmark.points[ii].x = pt(0);
00229 ptmark.points[ii].y = pt(2);
00230 ptmark.points[ii].z = -pt(1);
00231 }
00232
00233
00234 int ncams = vslam_.vo_.sba.nodes.size();
00235 cammark.points.resize(ncams*6);
00236 for (int i=0, ii=0; i<ncams; i++)
00237 {
00238 const Node &nd = vslam_.vo_.sba.nodes[i];
00239 Vector3d opt;
00240 Matrix<double,3,4> tr;
00241 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00242
00243 cammark.points[ii].x = nd.trans.x();
00244 cammark.points[ii].y = nd.trans.z();
00245 cammark.points[ii++].z = -nd.trans.y();
00246 opt = tr*Vector4d(0,0,0.3,1);
00247 cammark.points[ii].x = opt.x();
00248 cammark.points[ii].y = opt.z();
00249 cammark.points[ii++].z = -opt.y();
00250
00251 cammark.points[ii].x = nd.trans.x();
00252 cammark.points[ii].y = nd.trans.z();
00253 cammark.points[ii++].z = -nd.trans.y();
00254 opt = tr*Vector4d(0.2,0,0,1);
00255 cammark.points[ii].x = opt.x();
00256 cammark.points[ii].y = opt.z();
00257 cammark.points[ii++].z = -opt.y();
00258
00259 cammark.points[ii].x = nd.trans.x();
00260 cammark.points[ii].y = nd.trans.z();
00261 cammark.points[ii++].z = -nd.trans.y();
00262 opt = tr*Vector4d(0,0.1,0,1);
00263 cammark.points[ii].x = opt.x();
00264 cammark.points[ii].y = opt.z();
00265 cammark.points[ii++].z = -opt.y();
00266 }
00267
00268
00269 int num_tracks = vslam_.vo_.sba.tracks.size();
00270 int ii = cammark.points.size();
00271
00272 for (int i=0; i < num_tracks; i++)
00273 {
00274 const ProjMap &prjs = vslam_.vo_.sba.tracks[i].projections;
00275 for (ProjMap::const_iterator itr = prjs.begin(); itr != prjs.end(); itr++)
00276 {
00277 const Proj &prj = (*itr).second;
00278 if (prj.pointPlane)
00279 {
00280 cammark.points.resize(ii+2);
00281 Point pt0 = vslam_.vo_.sba.tracks[i].point;
00282 Vector3d plane_point = prj.plane_point;
00283 Vector3d plane_normal = prj.plane_normal;
00284 Eigen::Vector3d w = pt0.head<3>()-plane_point;
00285
00286 Eigen::Vector3d projpt = pt0.head<3>() - (w.dot(plane_normal))*plane_normal;
00287
00288 Vector3d pt1 = projpt;
00289
00290 cammark.points[ii].x = pt0.x();
00291 cammark.points[ii].y = pt0.z();
00292 cammark.points[ii++].z = -pt0.y();
00293 cammark.points[ii].x = pt1.x();
00294 cammark.points[ii].y = pt1.z();
00295 cammark.points[ii++].z = -pt1.y();
00296 }
00297 }
00298 }
00299
00300
00301 #if 0
00302
00303 int ncons = vslam_.vo_.spa.p2cons.size();
00304 cstmark.points.resize(ncons*6);
00305
00306 for (int i=0, ii=0; i<ncons; i++)
00307 {
00308 ConP2 &con = vslam_.vo_.spa.p2cons[i];
00309 Node &nd0 = vslam_.vo_.spa.nodes[con.ndr];
00310 Node &nd1 = vslam_.vo_.spa.nodes[con.nd1];
00311
00312 Node &nd = vslam_.vo_.spa.nodes[i];
00313 Vector3d opt;
00314 Matrix<double,3,4> tr;
00315 transformF2W(tr,nd.trans,Quaternion<double>(nd.qrot));
00316
00317 cstmark.points[ii].x = nd.trans.x();
00318 cstmark.points[ii].y = nd.trans.z();
00319 cstmark.points[ii++].z = -nd.trans.y();
00320 opt = tr*Vector4d(0,0,0.3,1);
00321 cstmark.points[ii].x = opt.x();
00322 cstmark.points[ii].y = opt.z();
00323 cstmark.points[ii++].z = -opt.y();
00324
00325 cstmark.points[ii].x = nd.trans.x();
00326 cstmark.points[ii].y = nd.trans.z();
00327 cstmark.points[ii++].z = -nd.trans.y();
00328 opt = tr*Vector4d(0.2,0,0,1);
00329 cstmark.points[ii].x = opt.x();
00330 cstmark.points[ii].y = opt.z();
00331 cstmark.points[ii++].z = -opt.y();
00332
00333 cstmark.points[ii].x = nd.trans.x();
00334 cstmark.points[ii].y = nd.trans.z();
00335 cstmark.points[ii++].z = -nd.trans.y();
00336 opt = tr*Vector4d(0,0.1,0,1);
00337 cstmark.points[ii].x = opt.x();
00338 cstmark.points[ii].y = opt.z();
00339 cstmark.points[ii++].z = -opt.y();
00340
00341 #if 0
00342 cstmark.points[ii].x = nd0.trans.x();
00343 cstmark.points[ii].y= nd0.trans.z();
00344 cstmark.points[ii++].z = -nd0.trans.y();
00345 cstmark.points[ii].x = nd1.trans.x();
00346 cstmark.points[ii].y = nd1.trans.z();
00347 cstmark.points[ii++].z = -nd1.trans.y();
00348 #endif
00349 }
00350 #endif // SPA
00351
00352 cam_pub_.publish(cammark);
00353 pt_pub_.publish(ptmark);
00354
00355
00356 }
00357
00358
00359 bool VisBundler::step( )
00360 {
00361 static boost::shared_ptr< sensor_msgs::CameraInfo > camera_info_left;
00362 static boost::shared_ptr< sensor_msgs::CameraInfo > camera_info_right;
00363 static boost::shared_ptr< sensor_msgs::Image > color_image;
00364 static boost::shared_ptr< stereo_msgs::DisparityImage > disparity_image;
00365
00366 static int message_count = 0;
00367 while( message_iterator_ != view_.end() )
00368 {
00369 if( message_iterator_->getTopic() == "/primesense/left/camera_info" )
00370 {
00371 camera_info_left = message_iterator_->instantiate<sensor_msgs::CameraInfo>();
00372 }
00373
00374 else if( message_iterator_->getTopic() == "/primesense/right/camera_info" )
00375 {
00376 camera_info_right = message_iterator_->instantiate<sensor_msgs::CameraInfo>();
00377 }
00378
00379 else if( message_iterator_->getTopic() == "/primesense/left/color_image_raw" )
00380 {
00381 color_image = message_iterator_->instantiate<sensor_msgs::Image>();
00382 }
00383 else if( message_iterator_->getTopic() == "/primesense/disparity" )
00384 {
00385 disparity_image = message_iterator_->instantiate<stereo_msgs::DisparityImage>();
00386 }
00387
00388 ++message_iterator_;
00389 ++message_count;
00390
00391 if( message_count > 3 )
00392 {
00393 ros::Time oldest = min( min( color_image->header.stamp, camera_info_right->header.stamp ) ,
00394 min( camera_info_left->header.stamp, disparity_image->header.stamp ) );
00395
00396 ros::Time newest = max( max( color_image->header.stamp, camera_info_right->header.stamp ) ,
00397 max( camera_info_left->header.stamp, disparity_image->header.stamp ) );
00398
00399 if( oldest == newest )
00400 {
00401 CamParams camera_params;
00402 camera_params.fx = camera_info_left->K[0];
00403 camera_params.fy = camera_info_left->K[4];
00404 camera_params.cx = camera_info_left->K[2];
00405 camera_params.cx = camera_info_left->K[5];
00406 camera_params.tx = - camera_info_right->P[3] / camera_params.fx;
00407
00408 static sensor_msgs::CvBridge cvImageBridge;
00409 cv::Mat image( cvImageBridge.imgMsgToCv( color_image ) );
00410
00411 cv::Mat grayImage;
00412 cv::cvtColor( image, grayImage, CV_RGB2GRAY );
00413 static sensor_msgs::CvBridge cvDisparityBridge;
00414 cvDisparityBridge.fromImage( disparity_image->image );
00415 cv::Mat disp_image32f = cvDisparityBridge.toIpl();
00416 cv::Mat disp_image16u;
00417
00418 disp_image32f.convertTo( disp_image16u, CV_16UC1, 32.0 );
00419
00420 bool is_keyframe = vslam_.addFrame( camera_params, grayImage, disp_image16u, 32.0, true );
00421
00422 if (is_keyframe)
00423 {
00424
00425 imshow("color image", image );
00426 vslam_.sba_.doSBA(10,1e-4,SBA_SPARSE_CHOLESKY);
00427
00429 int n = vslam_.sba_.nodes.size();
00430
00431
00432
00433 if (n%1 == 0)
00434 {
00435 drawgraph( 1 );
00436 publishRegisteredPointclouds( );
00437 drawgraph( 1 );
00438 publishRegisteredPointclouds( );
00439 for (int i=0; i<5; i++)
00440 {
00441
00442 cout << i << endl;
00443 vslam_.vo_.sba.doSBA( 1,1.0e-5,0 );
00444 drawgraph( 1 );
00445 publishRegisteredPointclouds( );
00446 drawgraph( 1 );
00447 publishRegisteredPointclouds( );
00448 }
00449 }
00450
00451
00452 if (n > 10 && n%500 == 0)
00453 {
00454 char fn[1024];
00455 sprintf(fn,"newcollege%d.g2o", n);
00456 sba::writeGraphFile(fn,vslam_.sba_);
00457 sprintf(fn,"newcollege%dm.g2o", n);
00458 sba::writeGraphFile(fn,vslam_.sba_,true);
00459 }
00460
00461 int nnsba = 10;
00462 if (n > 4 && n%nnsba == 0)
00463 {
00464 cout << "Running large SBA" << endl;
00465 vslam_.refine();
00466 }
00467
00468 break;
00469 }
00470 #ifdef VISMATCH
00471 cv::Mat display;
00472 drawVOtracks(grayImage, vslam_.vo_.frames, display);
00473 cv::imshow("VO tracks", display);
00474 #endif
00475 }
00476 }
00477 }
00478
00479 return (message_iterator_ != view_.end());
00480 }
00481
00482
00483 void VisBundler::spin()
00484 {
00485 bool quit = false;
00486 bool paused = true;
00487 while( node_handle_.ok() && !quit )
00488 {
00489 ros::spinOnce();
00490 char key = cv::waitKey( 10 ) & 0xFF;
00491 switch( key )
00492 {
00493 case 27:
00494 case 'Q':
00495 case 'q':
00496 quit = true;
00497 break;
00498 case ' ':
00499 paused = !paused;
00500 break;
00501 case 's':
00502 case 'S':
00503 paused = true;
00504 step();
00505 break;
00506 }
00507 if( !paused )
00508 {
00509 step();
00510 }
00511 }
00512 }
00513
00514 int main(int argc, char** argv)
00515 {
00516 if (argc < 5)
00517 {
00518 cout <<"Usage: " << argv[0] << " <bag file> <vocab tree file> <vocab weights file> <calonder trees file>" << endl;
00519 exit(0);
00520 }
00521
00522
00523 ros::init(argc, argv, "VisBundler");
00524 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00525 typedef cv::SiftDescriptorExtractor Sift;
00526 VisBundler visbundler( argv[1], argv[2], argv[3], new Calonder(argv[4]) );
00527
00528 visbundler.spin();
00529
00530 return 0;
00531 }