00001 #include <ros/ros.h>
00002 #include <image_transport/image_transport.h>
00003 #include <image_transport/subscriber_filter.h>
00004 #include <message_filters/subscriber.h>
00005 #include <message_filters/time_synchronizer.h>
00006 #include <dynamic_reconfigure/server.h>
00007
00008 #include <cv_bridge/CvBridge.h>
00009 #include <image_geometry/stereo_camera_model.h>
00010
00011 #include <vslam_system/vslam.h>
00012 #include <sba/visualization.h>
00013 #include <vslam_system/any_detector.h>
00014 #include <vslam_system/StereoVslamNodeConfig.h>
00015
00016
00017 #include <sba/Frame.h>
00018 #include <geometry_msgs/PointStamped.h>
00019
00020
00021
00022
00023 static const double MAX_KEYFRAME_DISTANCE = 0.2;
00024 static const double MAX_KEYFRAME_ANGLE = 0.1;
00025 static const int MIN_KEYFRAME_INLIERS = 0;
00026
00027 using namespace vslam;
00028
00029 class VONode
00030 {
00031 private:
00032 ros::NodeHandle nh_;
00033 image_transport::ImageTransport it_;
00034
00035
00036 image_transport::SubscriberFilter l_image_sub_, r_image_sub_;
00037 message_filters::Subscriber<sensor_msgs::CameraInfo> l_info_sub_, r_info_sub_;
00038 message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo,
00039 sensor_msgs::Image, sensor_msgs::CameraInfo> sync_;
00040
00041
00042 ros::Publisher sba_frames_pub_;
00043
00044
00045 image_transport::CameraPublisher vo_tracks_pub_;
00046 cv::Mat vo_display_;
00047
00048
00049 sensor_msgs::CvBridge l_bridge_, r_bridge_;
00050 image_geometry::StereoCameraModel cam_model_;
00051 cv::Ptr<cv::FeatureDetector> detector_;
00052
00053 frame_common::FrameProc frame_processor_;
00055 std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> > frames_;
00056 vslam::voSt vo_;
00057
00058 int numframes;
00059 int numpoints;
00060 int numcameras;
00061
00062 vector<sba::Projection> proj_msgs;
00063 vector<sba::WorldPoint> point_msgs;
00064 vector<sba::CameraNode> node_msgs;
00065
00066
00067 typedef dynamic_reconfigure::Server<vslam_system::StereoVslamNodeConfig> ReconfigureServer;
00068 ReconfigureServer reconfigure_server_;
00069
00070 bool init;
00071
00072 public:
00073
00074 VONode(const std::string& vocab_tree_file, const std::string& vocab_weights_file,
00075 const std::string& calonder_trees_file)
00076 : it_(nh_), sync_(3),
00077 detector_(new vslam_system::AnyDetector),
00078 vo_(boost::shared_ptr<pe::PoseEstimator>(new pe::PoseEstimator3d(1000,true,6.0,8.0,8.0)),
00079 40, 10, MIN_KEYFRAME_INLIERS, MAX_KEYFRAME_DISTANCE, MAX_KEYFRAME_ANGLE),
00080 numframes(0), numpoints(0), numcameras(0), init(true)
00081 {
00082
00083 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00084 frame_processor_.setFrameDescriptor(new Calonder(calonder_trees_file));
00085
00086
00087 l_image_sub_.subscribe(it_, "left/image_rect", 1);
00088 l_info_sub_ .subscribe(nh_, "left/camera_info", 1);
00089 r_image_sub_.subscribe(it_, "right/image_rect", 1);
00090 r_info_sub_ .subscribe(nh_, "right/camera_info", 1);
00091 vo_tracks_pub_ = it_.advertiseCamera("/vo/vo_tracks/image", 1);
00092 sync_.connectInput(l_image_sub_, l_info_sub_, r_image_sub_, r_info_sub_);
00093 sync_.registerCallback( boost::bind(&VONode::imageCb, this, _1, _2, _3, _4) );
00094
00095
00096
00097
00098 sba_frames_pub_ = nh_.advertise<sba::Frame>("/sba/frames", 5000);
00099
00100
00101 ReconfigureServer::CallbackType f = boost::bind(&VONode::configCb, this, _1, _2);
00102 reconfigure_server_.setCallback(f);
00103 }
00104
00105 void imageCb(const sensor_msgs::ImageConstPtr& l_image,
00106 const sensor_msgs::CameraInfoConstPtr& l_cam_info,
00107 const sensor_msgs::ImageConstPtr& r_image,
00108 const sensor_msgs::CameraInfoConstPtr& r_cam_info)
00109 {
00110 ROS_INFO("In callback, seq = %u", l_cam_info->header.seq);
00111
00112
00113 cv::Mat left, right;
00114 try
00115 {
00116 left = l_bridge_.imgMsgToCv(l_image, "mono8");
00117 right = r_bridge_.imgMsgToCv(r_image, "mono8");
00118 }
00119 catch (sensor_msgs::CvBridgeException& e)
00120 {
00121 ROS_ERROR("Conversion error: %s", e.what());
00122 return;
00123 }
00124 cam_model_.fromCameraInfo(l_cam_info, r_cam_info);
00125
00126 frame_common::CamParams cam_params;
00127 cam_params.fx = cam_model_.left().fx();
00128 cam_params.fy = cam_model_.left().fy();
00129 cam_params.cx = cam_model_.left().cx();
00130 cam_params.cy = cam_model_.left().cy();
00131 cam_params.tx = cam_model_.baseline();
00132
00133 if (addFrame(cam_params, left, right))
00134 {
00135 if (vo_tracks_pub_.getNumSubscribers() > 0)
00136 {
00137 frame_common::drawVOtracks(left, vo_.frames, vo_display_);
00138 IplImage ipl = vo_display_;
00139 sensor_msgs::ImagePtr msg = sensor_msgs::CvBridge::cvToImgMsg(&ipl);
00140 msg->header = l_cam_info->header;
00141 vo_tracks_pub_.publish(msg, l_cam_info);
00142 }
00143 }
00144 }
00145
00146 void configCb(vslam_system::StereoVslamNodeConfig& config, uint32_t level)
00147 {
00148 dynamic_cast<vslam_system::AnyDetector*>((cv::FeatureDetector*)detector_)->update(config);
00149 frame_processor_.detector = detector_;
00150
00151
00152
00153
00154
00155 }
00156
00157 bool addFrame(const frame_common::CamParams& camera_parameters,
00158 const cv::Mat& left, const cv::Mat& right)
00159 {
00160
00161 frame_common::Frame next_frame;
00162 next_frame.setCamParams(camera_parameters);
00163 frame_processor_.setStereoFrame(next_frame, left, right);
00164 next_frame.frameId = numframes++;
00165 next_frame.img = cv::Mat();
00166 next_frame.imgRight = cv::Mat();
00167
00168
00169 bool is_keyframe = vo_.addFrame(next_frame);
00170
00171
00172 if (is_keyframe)
00173 {
00174 frames_.push_back(next_frame);
00175 publishLatestFrame();
00176 }
00177
00178 return is_keyframe;
00179 }
00180
00181 void publishLatestFrame()
00182 {
00183 if (sba_frames_pub_.getNumSubscribers() > 0)
00184 {
00185
00186 proj_msgs.clear();
00187 node_msgs.clear();
00188 point_msgs.clear();
00189
00190
00191
00192
00193
00194
00195 frame_common::Frame &f1 = frames_.back();
00196
00197
00198 f1.ipts.assign(f1.kpts.size(), -1);
00199
00200
00201 Quaterniond fq;
00202 Vector4d trans;
00203 Matrix<double,3,4> f2w;
00204
00205 if (init)
00206 {
00207 trans = Vector4d(0,0,0,1);
00208 fq.coeffs() = Vector4d(0,0,0,1);
00209 fq.normalize();
00210 }
00211 else
00212 {
00213
00214 sba::Node &nd0 = *(vo_.sba.nodes.end()-1);
00215 sba::Node &nd1 = vo_.sba.nodes.back();
00216 fq = nd1.qrot;
00217 trans = nd1.trans;
00218
00219 sba::transformF2W(f2w,nd0.trans,nd0.qrot);
00220
00221 }
00222
00223
00224
00225 int cameraindex = publishNode(trans, fq, f1.cam, init);
00226
00227 if (init)
00228 {
00229 init = false;
00230 return;
00231 }
00232
00235
00237 frame_common::Frame &f0 = *(frames_.end()-2);
00238 addProjections(f0, f1, vo_.pose_estimator_->inliers, f2w, cameraindex-1, cameraindex);
00239
00240 publishFrame();
00241 }
00242 }
00243
00244 void publishFrame()
00245 {
00246 sba::Frame msg;
00247 msg.nodes = node_msgs;
00248 msg.points = point_msgs;
00249 msg.projections = proj_msgs;
00250
00251 sba_frames_pub_.publish(msg);
00252 }
00253
00254 int publishNode(Eigen::Matrix<double,4,1> trans,
00255 Eigen::Quaternion<double> fq,
00256 const frame_common::CamParams &cp,
00257 bool isFixed)
00258 {
00259 sba::CameraNode msg;
00260
00261 msg.index = numcameras;
00262
00263 msg.transform.translation.x = trans.x();
00264 msg.transform.translation.y = trans.y();
00265 msg.transform.translation.z = trans.z();
00266 msg.transform.rotation.x = fq.x();
00267 msg.transform.rotation.y = fq.y();
00268 msg.transform.rotation.z = fq.z();
00269 msg.transform.rotation.w = fq.w();
00270 msg.fx = cp.fx;
00271 msg.fy = cp.fy;
00272 msg.cx = cp.cx;
00273 msg.cy = cp.cy;
00274 msg.baseline = cp.tx;
00275 msg.fixed = isFixed;
00276
00277 node_msgs.push_back(msg);
00278
00279 return numcameras++;
00280
00281 }
00282
00283 int publishPoint(sba::Point pt)
00284 {
00285 sba::WorldPoint msg;
00286
00287 msg.index = numpoints;
00288
00289 msg.x = pt.x();
00290 msg.y = pt.y();
00291 msg.z = pt.z();
00292 msg.w = pt.w();
00293
00294 point_msgs.push_back(msg);
00295
00296 return numpoints++;
00297
00298
00299 }
00300
00301 void publishProjection(int ci, int pi, Eigen::Vector3d &q, bool stereo)
00302 {
00303 sba::Projection msg;
00304 msg.camindex = ci;
00305 msg.pointindex = pi;
00306 msg.u = q.x();
00307 msg.v = q.y();
00308 msg.d = q.z();
00309 msg.stereo = stereo;
00310 msg.usecovariance = false;
00311
00312 proj_msgs.push_back(msg);
00313 }
00314
00315
00316 void addProjections(fc::Frame &f0, fc::Frame &f1,
00317 const std::vector<cv::DMatch> &inliers,
00318 const Matrix<double,3,4>& f2w, int ndi0, int ndi1)
00319 {
00320
00321 vector<bool> matched0(f0.ipts.size(),0);
00322 vector<bool> matched1(f1.ipts.size(),0);
00323
00324
00325 for (int i=0; i<(int)inliers.size(); i++)
00326 {
00327 int i0 = inliers[i].queryIdx;
00328 int i1 = inliers[i].trainIdx;
00329
00330 if (matched0[i0]) continue;
00331 if (matched1[i1]) continue;
00332 matched0[i0] = true;
00333 matched1[i1] = true;
00334
00335 int pti;
00336
00337 if (f0.ipts[i0] < 0 && f1.ipts[i1] < 0)
00338 {
00339 Vector4d pt;
00340 pt.head(3) = f2w*f0.pts[i0];
00341 pt(3) = 1.0;
00342
00343 pti = publishPoint(pt);
00344 f0.ipts[i0] = pti;
00345 f1.ipts[i1] = pti;
00346
00347 vo_.ipts.push_back(-1);
00348
00349 Vector3d ipt = getProjection(f0, i0);
00350 publishProjection(ndi0, pti, ipt, true);
00351
00352
00353 ipt = getProjection(f1, i1);
00354 publishProjection(ndi1, pti, ipt, true);
00355 }
00356
00357
00358 else if (f0.ipts[i0] >= 0 && f1.ipts[i1] >= 0)
00359 {
00360 if (f0.ipts[i0] != f1.ipts[i1])
00361 {
00362
00363
00364 printf("We are trying to merge tracks %d and %d with ipts %d and %d\n", i0, i1, f0.ipts[i0], f1.ipts[i1]);
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380
00381
00382
00383
00384
00385
00386 }
00387 }
00388
00389 else if (f1.ipts[i1] < 0)
00390 {
00391 pti = f0.ipts[i0];
00392 f1.ipts[i1] = pti;
00393
00394
00395 Vector3d ipt = getProjection(f1, i1);
00396 publishProjection(ndi1, pti, ipt, true);
00397 }
00398 else if (f0.ipts[i0] < 0)
00399 {
00400 pti = f1.ipts[i1];
00401 f0.ipts[i0] = pti;
00402
00403
00404 Vector3d ipt = getProjection(f0, i0);
00405 publishProjection(ndi0, pti, ipt, true);
00406 }
00407 }
00408 }
00409
00410 };
00411
00412 int main(int argc, char** argv)
00413 {
00414 ros::init(argc, argv, "stereo_vo");
00415 if (argc < 4) {
00416 printf("Usage: %s <vocab tree file> <vocab weights file> <calonder trees file>\n", argv[0]);
00417 return 1;
00418 }
00419
00420 VONode vonode(argv[1], argv[2], argv[3]);
00421 ros::spin();
00422 }
00423