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 #include <tf/transform_broadcaster.h>
00017 #include <tf/transform_listener.h>
00018 #include <nav_msgs/Odometry.h>
00019 #include <geometry_msgs/PoseStamped.h>
00020
00021 #include <pcl/point_types.h>
00022 #include <pcl/point_cloud.h>
00023
00024 void publishRegisteredPointclouds(sba::SysSBA& sba,
00025 std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> >& frames,
00026 ros::Publisher& pub);
00027
00028 class StereoVslamNode
00029 {
00030 private:
00031 ros::NodeHandle nh_;
00032 image_transport::ImageTransport it_;
00033
00034
00035 image_transport::SubscriberFilter l_image_sub_, r_image_sub_;
00036 message_filters::Subscriber<sensor_msgs::CameraInfo> l_info_sub_, r_info_sub_;
00037 message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo,
00038 sensor_msgs::Image, sensor_msgs::CameraInfo> sync_;
00039
00040
00041 ros::Publisher cam_marker_pub_;
00042 ros::Publisher point_marker_pub_;
00043 image_transport::CameraPublisher vo_tracks_pub_;
00044 cv::Mat vo_display_;
00045 ros::Publisher odom_pub_;
00046 tf::TransformBroadcaster tf_broadcast_;
00047 tf::TransformListener tf_listener_;
00048 tf::Transform tf_transform_;
00049 ros::Publisher pointcloud_pub_;
00050
00051
00052 sensor_msgs::CvBridge l_bridge_, r_bridge_;
00053 image_geometry::StereoCameraModel cam_model_;
00054 vslam::VslamSystem vslam_system_;
00055 cv::Ptr<cv::FeatureDetector> detector_;
00056
00057 typedef dynamic_reconfigure::Server<vslam_system::StereoVslamNodeConfig> ReconfigureServer;
00058 ReconfigureServer reconfigure_server_;
00059
00060 public:
00061
00062 StereoVslamNode(const std::string& vocab_tree_file, const std::string& vocab_weights_file,
00063 const std::string& calonder_trees_file)
00064 : it_(nh_), sync_(3),
00065 vslam_system_(vocab_tree_file, vocab_weights_file),
00066 detector_(new vslam_system::AnyDetector)
00067 {
00068
00069 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00070 vslam_system_.frame_processor_.setFrameDescriptor(new Calonder(calonder_trees_file));
00071
00072
00073 cam_marker_pub_ = nh_.advertise<visualization_msgs::Marker>("/vslam/cameras", 1);
00074 point_marker_pub_ = nh_.advertise<visualization_msgs::Marker>("/vslam/points", 1);
00075 vo_tracks_pub_ = it_.advertiseCamera("/vslam/vo_tracks/image", 1);
00076 odom_pub_ = nh_.advertise<nav_msgs::Odometry>("/vo", 1);
00077 pointcloud_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("/vslam/pointcloud", 1);
00078
00079
00080 l_image_sub_.subscribe(it_, "left/image_rect", 1);
00081 l_info_sub_ .subscribe(nh_, "left/camera_info", 1);
00082 r_image_sub_.subscribe(it_, "right/image_rect", 1);
00083 r_info_sub_ .subscribe(nh_, "right/camera_info", 1);
00084 sync_.connectInput(l_image_sub_, l_info_sub_, r_image_sub_, r_info_sub_);
00085 sync_.registerCallback( boost::bind(&StereoVslamNode::imageCb, this, _1, _2, _3, _4) );
00086
00087
00088 ReconfigureServer::CallbackType f = boost::bind(&StereoVslamNode::configCb, this, _1, _2);
00089 reconfigure_server_.setCallback(f);
00090
00091 }
00092
00093 void configCb(vslam_system::StereoVslamNodeConfig& config, uint32_t level)
00094 {
00095 dynamic_cast<vslam_system::AnyDetector*>((cv::FeatureDetector*)detector_)->update(config);
00096 vslam_system_.frame_processor_.detector = detector_;
00097
00098 vslam_system_.setPRRansacIt(config.pr_ransac_iterations);
00099 vslam_system_.setPRPolish(config.pr_polish);
00100 vslam_system_.setVORansacIt(config.vo_ransac_iterations);
00101 vslam_system_.setVOPolish(config.vo_polish);
00102 }
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 left = l_bridge_.imgMsgToCv(l_image, "mono8");
00116 right = r_bridge_.imgMsgToCv(r_image, "mono8");
00117 }
00118 catch (sensor_msgs::CvBridgeException& e) {
00119 ROS_ERROR("Conversion error: %s", e.what());
00120 return;
00121 }
00122 cam_model_.fromCameraInfo(l_cam_info, r_cam_info);
00123
00124 frame_common::CamParams cam_params;
00125 cam_params.fx = cam_model_.left().fx();
00126 cam_params.fy = cam_model_.left().fy();
00127 cam_params.cx = cam_model_.left().cx();
00128 cam_params.cy = cam_model_.left().cy();
00129 cam_params.tx = cam_model_.baseline();
00130
00131 if (vslam_system_.addFrame(cam_params, left, right)) {
00133 int size = vslam_system_.sba_.nodes.size();
00134 if (size % 2 == 0) {
00135
00136 sba::drawGraph(vslam_system_.sba_, cam_marker_pub_, point_marker_pub_);
00137 }
00138
00139
00140 if (vo_tracks_pub_.getNumSubscribers() > 0) {
00141 frame_common::drawVOtracks(left, vslam_system_.vo_.frames, vo_display_);
00142 IplImage ipl = vo_display_;
00143 sensor_msgs::ImagePtr msg = sensor_msgs::CvBridge::cvToImgMsg(&ipl);
00144 msg->header = l_cam_info->header;
00145 vo_tracks_pub_.publish(msg, l_cam_info);
00146 }
00147
00148
00149 const int LARGE_SBA_INTERVAL = 10;
00150 if (size > 4 && size % LARGE_SBA_INTERVAL == 0) {
00151 ROS_INFO("Running large SBA on %d nodes", size);
00152 vslam_system_.refine();
00153 }
00154
00155 if (pointcloud_pub_.getNumSubscribers() > 0 && size % 2 == 0)
00156 publishRegisteredPointclouds(vslam_system_.sba_, vslam_system_.frames_, pointcloud_pub_);
00157
00158
00159 if (0)
00160 {
00161 ros::Time stamp = l_cam_info->header.stamp;
00162 std::string image_frame = l_cam_info->header.frame_id;
00163 Eigen::Vector4d trans = -vslam_system_.sba_.nodes.back().trans;
00164 Eigen::Quaterniond rot = vslam_system_.sba_.nodes.back().qrot.conjugate();
00165
00166 trans.head<3>() = rot.toRotationMatrix()*trans.head<3>();
00167
00168 tf_transform_.setOrigin(tf::Vector3(trans(0), trans(1), trans(2)));
00169 tf_transform_.setRotation(tf::Quaternion(rot.x(), rot.y(), rot.z(), rot.w()) );
00170
00171 tf::Transform simple_transform;
00172 simple_transform.setOrigin(tf::Vector3(0, 0, 0));
00173 simple_transform.setRotation(tf::Quaternion(.5, -.5, .5, .5));
00174
00175 tf_broadcast_.sendTransform(tf::StampedTransform(tf_transform_, stamp, image_frame, "visual_odom"));
00176 tf_broadcast_.sendTransform(tf::StampedTransform(simple_transform, stamp, "visual_odom", "pgraph"));
00177
00178
00179
00180 if (odom_pub_.getNumSubscribers() > 0)
00181 {
00182 tf::StampedTransform base_to_image;
00183 tf::Transform base_to_visodom;
00184
00185 try
00186 {
00187 tf_listener_.lookupTransform(image_frame, "/base_footprint",
00188 stamp, base_to_image);
00189 }
00190 catch (tf::TransformException ex)
00191 {
00192 ROS_WARN("%s",ex.what());
00193 return;
00194 }
00195
00196 base_to_visodom = tf_transform_.inverse() * base_to_image;
00197
00198 geometry_msgs::PoseStamped pose;
00199 nav_msgs::Odometry odom;
00200 pose.header.frame_id = "/visual_odom";
00201 pose.pose.position.x = base_to_visodom.getOrigin().x();
00202 pose.pose.position.y = base_to_visodom.getOrigin().y();
00203 pose.pose.position.z = base_to_visodom.getOrigin().z();
00204 pose.pose.orientation.x = base_to_visodom.getRotation().x();
00205 pose.pose.orientation.y = base_to_visodom.getRotation().y();
00206 pose.pose.orientation.z = base_to_visodom.getRotation().z();
00207 pose.pose.orientation.w = base_to_visodom.getRotation().w();
00208
00209 odom.header.stamp = stamp;
00210 odom.header.frame_id = "/visual_odom";
00211 odom.child_frame_id = "/base_footprint";
00212 odom.pose.pose = pose.pose;
00213
00214
00215
00216
00217
00218
00219 odom_pub_.publish(odom);
00220 }
00221 }
00222 }
00223 }
00224 };
00225
00226 void publishRegisteredPointclouds(sba::SysSBA& sba,
00227 std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> >& frames,
00228 ros::Publisher& pub)
00229 {
00230 pcl::PointCloud<pcl::PointXYZRGB> cloud;
00231
00232
00233 unsigned int totalpoints = 0;
00234 for (size_t i = 0; i < frames.size(); i++)
00235 {
00236 totalpoints += frames[i].pts.size();
00237 }
00238
00239 cloud.points.resize(totalpoints);
00240 unsigned int k = 0;
00241
00242 for(size_t i=0; i < frames.size(); i++)
00243 {
00244 if (sba.nodes.size() < i)
00245 break;
00246 Eigen::Matrix3d rotmat = sba.nodes[i].qrot.toRotationMatrix();
00247 Eigen::Vector3d trans = sba.nodes[i].trans.head<3>();
00248
00249 for (size_t j=0; j < frames[i].pts.size(); j++)
00250 {
00251
00252 if (frames[i].pts[j].z() > 30.0 || frames[i].pts[j].z() < 0.1)
00253 continue;
00254 Eigen::Vector3d point(frames[i].pts[j].x(), frames[i].pts[j].y(), frames[i].pts[j].z());
00255 point = rotmat*point + trans;
00256
00257 cloud.points[k].x = point(2);
00258 cloud.points[k].y = -point(0);
00259 cloud.points[k].z = -point(1);
00260
00261 unsigned char r(255), g(255), b(255);
00262
00263 int32_t rgb_packed = (r << 16) | (g << 8) | b;
00264 memcpy (&cloud.points[k].rgb, &rgb_packed, sizeof (int32_t));
00265 k++;
00266 }
00267 }
00268
00269 sensor_msgs::PointCloud2 cloud_out;
00270 pcl::toROSMsg (cloud, cloud_out);
00271 cloud_out.header.frame_id = "/pgraph";
00272 pub.publish (cloud_out);
00273 }
00274
00275 int main(int argc, char** argv) {
00276 ros::init(argc, argv, "stereo_vslam");
00277 if (argc < 4) {
00278 printf("Usage: %s <vocab tree file> <vocab weights file> <calonder trees file>\n", argv[0]);
00279 return 1;
00280 }
00281
00282 StereoVslamNode vslam(argv[1], argv[2], argv[3]);
00283 ros::spin();
00284 }