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/pinhole_camera_model.h>
00010
00011 #include <vslam_system/vslam_mono.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 static const double PI = 3.14159265;
00022
00023 class StereoVslamNode
00024 {
00025 private:
00026 ros::NodeHandle nh_;
00027 image_transport::ImageTransport it_;
00028
00029
00030 image_transport::SubscriberFilter l_image_sub_;
00031 message_filters::Subscriber<sensor_msgs::CameraInfo> l_info_sub_;
00032 message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo> sync_;
00033
00034
00035 ros::Publisher cam_marker_pub_;
00036 ros::Publisher point_marker_pub_;
00037 image_transport::CameraPublisher vo_tracks_pub_;
00038 cv::Mat vo_display_;
00039 ros::Publisher odom_pub_;
00040 tf::TransformBroadcaster tf_broadcast_;
00041 tf::TransformListener tf_listener_;
00042 tf::Transform tf_transform_;
00043
00044
00045 sensor_msgs::CvBridge l_bridge_, r_bridge_;
00046 image_geometry::PinholeCameraModel cam_model_;
00047 vslam::VslamSystemMono vslam_system_;
00048 cv::Ptr<cv::FeatureDetector> detector_;
00049
00050 typedef dynamic_reconfigure::Server<vslam_system::StereoVslamNodeConfig> ReconfigureServer;
00051 ReconfigureServer reconfigure_server_;
00052
00053 public:
00054
00055 StereoVslamNode(const std::string& vocab_tree_file, const std::string& vocab_weights_file,
00056 const std::string& calonder_trees_file)
00057 : it_(nh_), sync_(1),
00058 vslam_system_(vocab_tree_file, vocab_weights_file),
00059 detector_(new vslam_system::AnyDetector)
00060 {
00061
00062 typedef cv::CalonderDescriptorExtractor<float> Calonder;
00063 vslam_system_.frame_processor_.setFrameDescriptor(new Calonder(calonder_trees_file));
00064
00065
00066 cam_marker_pub_ = nh_.advertise<visualization_msgs::Marker>("/vslam/cameras", 1);
00067 point_marker_pub_ = nh_.advertise<visualization_msgs::Marker>("/vslam/points", 1);
00068 vo_tracks_pub_ = it_.advertiseCamera("/vslam/vo_tracks/image", 1);
00069 odom_pub_ = nh_.advertise<nav_msgs::Odometry>("/vo", 1);
00070
00071
00072 l_image_sub_.subscribe(it_, "image_rect", 1);
00073 l_info_sub_ .subscribe(nh_, "camera_info", 1);
00074 sync_.connectInput(l_image_sub_, l_info_sub_);
00075 sync_.registerCallback( boost::bind(&StereoVslamNode::imageCb, this, _1, _2) );
00076
00077
00078 ReconfigureServer::CallbackType f = boost::bind(&StereoVslamNode::configCb, this, _1, _2);
00079 reconfigure_server_.setCallback(f);
00080
00081 }
00082
00083 void configCb(vslam_system::StereoVslamNodeConfig& config, uint32_t level)
00084 {
00085 dynamic_cast<vslam_system::AnyDetector*>((cv::FeatureDetector*)detector_)->update(config);
00086 vslam_system_.frame_processor_.detector = detector_;
00087
00088 vslam_system_.setPRRansacIt(config.pr_ransac_iterations);
00089 vslam_system_.setPRPolish(config.pr_polish);
00090 vslam_system_.setVORansacIt(config.vo_ransac_iterations);
00091 vslam_system_.setVOPolish(config.vo_polish);
00092 }
00093
00094
00095 void imageCb(const sensor_msgs::ImageConstPtr& l_image,
00096 const sensor_msgs::CameraInfoConstPtr& l_cam_info)
00097 {
00098 ROS_INFO("In callback, seq = %u", l_cam_info->header.seq);
00099
00100
00101 cv::Mat left;
00102 try
00103 {
00104 left = l_bridge_.imgMsgToCv(l_image, "mono8");
00105 }
00106 catch (sensor_msgs::CvBridgeException& e)
00107 {
00108 ROS_ERROR("Conversion error: %s", e.what());
00109 return;
00110 }
00111 cam_model_.fromCameraInfo(l_cam_info);
00112
00113 frame_common::CamParams cam_params;
00114 cam_params.fx = cam_model_.fx();
00115 cam_params.fy = cam_model_.fy();
00116 cam_params.cx = cam_model_.cx();
00117 cam_params.cy = cam_model_.cy();
00118 cam_params.tx = 0.0;
00119
00120 if (vslam_system_.addFrame(cam_params, left)) {
00122 int size = vslam_system_.sba_.nodes.size();
00123 if (size % 2 == 0) {
00124
00125 sba::drawGraph(vslam_system_.sba_, cam_marker_pub_, point_marker_pub_);
00126 }
00127
00128
00129 if (vo_tracks_pub_.getNumSubscribers() > 0) {
00130 frame_common::drawVOtracks(left, vslam_system_.vo_.frames, vo_display_);
00131 IplImage ipl = vo_display_;
00132 sensor_msgs::ImagePtr msg = sensor_msgs::CvBridge::cvToImgMsg(&ipl);
00133 msg->header = l_cam_info->header;
00134 vo_tracks_pub_.publish(msg, l_cam_info);
00135 }
00136
00137
00138 const int LARGE_SBA_INTERVAL = 10;
00139 if (size > 4 && size % LARGE_SBA_INTERVAL == 0) {
00140 ROS_INFO("Running large SBA on %d nodes", size);
00141 vslam_system_.refine();
00142 }
00143
00144
00145 ros::Time stamp = l_cam_info->header.stamp;
00146 std::string image_frame = l_cam_info->header.frame_id;
00147 Eigen::Vector4d trans = -vslam_system_.sba_.nodes.back().trans;
00148 Eigen::Quaterniond rot = vslam_system_.sba_.nodes.back().qrot.conjugate();
00149
00150 trans.head<3>() = rot.toRotationMatrix()*trans.head<3>();
00151
00152 tf_transform_.setOrigin(tf::Vector3(trans(0), trans(1), trans(2)));
00153 tf_transform_.setRotation(tf::Quaternion(rot.x(), rot.y(), rot.z(), rot.w()) );
00154
00155 tf::Transform simple_transform;
00156 simple_transform.setOrigin(tf::Vector3(0, 0, 0));
00157 simple_transform.setRotation(tf::Quaternion(.5, -.5, .5, .5));
00158
00159 tf_broadcast_.sendTransform(tf::StampedTransform(tf_transform_, stamp, image_frame, "visual_odom"));
00160 tf_broadcast_.sendTransform(tf::StampedTransform(simple_transform, stamp, "visual_odom", "pgraph"));
00161
00162
00163
00164
00165 if (odom_pub_.getNumSubscribers() > 0)
00166 {
00167 tf::StampedTransform base_to_image;
00168 tf::Transform base_to_visodom;
00169
00170 try
00171 {
00172 tf_listener_.lookupTransform(image_frame, "/base_footprint",
00173 stamp, base_to_image);
00174 }
00175 catch (tf::TransformException ex)
00176 {
00177 ROS_WARN("%s",ex.what());
00178 return;
00179 }
00180
00181
00182 base_to_visodom = tf_transform_.inverse() * base_to_image;
00183
00184 geometry_msgs::PoseStamped pose;
00185 nav_msgs::Odometry odom;
00186 pose.header.frame_id = "/visual_odom";
00187 pose.pose.position.x = base_to_visodom.getOrigin().x();
00188 pose.pose.position.y = base_to_visodom.getOrigin().y();
00189 pose.pose.position.z = base_to_visodom.getOrigin().z();
00190 pose.pose.orientation.x = base_to_visodom.getRotation().x();
00191 pose.pose.orientation.y = base_to_visodom.getRotation().y();
00192 pose.pose.orientation.z = base_to_visodom.getRotation().z();
00193 pose.pose.orientation.w = base_to_visodom.getRotation().w();
00194
00195 odom.header.stamp = stamp;
00196 odom.header.frame_id = "/visual_odom";
00197 odom.child_frame_id = "/base_footprint";
00198 odom.pose.pose = pose.pose;
00199
00200
00201
00202
00203
00204
00205 odom_pub_.publish(odom);
00206 }
00207 }
00208 }
00209 };
00210
00211 int main(int argc, char** argv) {
00212 ros::init(argc, argv, "stereo_vslam");
00213 if (argc < 4) {
00214 printf("Usage: %s <vocab tree file> <vocab weights file> <calonder trees file>\n", argv[0]);
00215 return 1;
00216 }
00217
00218 StereoVslamNode vslam(argv[1], argv[2], argv[3]);
00219 ros::spin();
00220 }