00001 #include <ros/ros.h>
00002 #include <sensor_msgs/image_encodings.h>
00003 #include <image_geometry/stereo_camera_model.h>
00004 #include <cv_bridge/cv_bridge.h>
00005 #include <pcl_ros/point_cloud.h>
00006 #include <pcl/point_types.h>
00007
00008 #include <viso_stereo.h>
00009
00010 #include <viso2_ros/VisoInfo.h>
00011
00012 #include "stereo_processor.h"
00013 #include "odometer_base.h"
00014 #include "odometry_params.h"
00015
00016
00017 #include <opencv2/highgui/highgui.hpp>
00018
00019 namespace viso2_ros
00020 {
00021
00022
00023 static const boost::array<double, 36> STANDARD_POSE_COVARIANCE =
00024 { { 0.1, 0, 0, 0, 0, 0,
00025 0, 0.1, 0, 0, 0, 0,
00026 0, 0, 0.1, 0, 0, 0,
00027 0, 0, 0, 0.17, 0, 0,
00028 0, 0, 0, 0, 0.17, 0,
00029 0, 0, 0, 0, 0, 0.17 } };
00030 static const boost::array<double, 36> STANDARD_TWIST_COVARIANCE =
00031 { { 0.05, 0, 0, 0, 0, 0,
00032 0, 0.05, 0, 0, 0, 0,
00033 0, 0, 0.05, 0, 0, 0,
00034 0, 0, 0, 0.09, 0, 0,
00035 0, 0, 0, 0, 0.09, 0,
00036 0, 0, 0, 0, 0, 0.09 } };
00037 static const boost::array<double, 36> BAD_COVARIANCE =
00038 { { 9999, 0, 0, 0, 0, 0,
00039 0, 9999, 0, 0, 0, 0,
00040 0, 0, 9999, 0, 0, 0,
00041 0, 0, 0, 9999, 0, 0,
00042 0, 0, 0, 0, 9999, 0,
00043 0, 0, 0, 0, 0, 9999 } };
00044
00045
00046 class StereoOdometer : public StereoProcessor, public OdometerBase
00047 {
00048
00049 private:
00050
00051 boost::shared_ptr<VisualOdometryStereo> visual_odometer_;
00052 VisualOdometryStereo::parameters visual_odometer_params_;
00053
00054 ros::Publisher point_cloud_pub_;
00055 ros::Publisher info_pub_;
00056
00057 bool got_lost_;
00058
00059
00060 int ref_frame_change_method_;
00061 bool keep_reference_frame_;
00062 double ref_frame_motion_threshold_;
00063 int ref_frame_inlier_threshold_;
00064 Matrix reference_motion_;
00065
00066 public:
00067
00068 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
00069
00070 StereoOdometer(const std::string& transport) :
00071 StereoProcessor(transport), OdometerBase(),
00072 got_lost_(false), keep_reference_frame_(false)
00073 {
00074
00075 ros::NodeHandle local_nh("~");
00076 odometry_params::loadParams(local_nh, visual_odometer_params_);
00077
00078 local_nh.param("ref_frame_change_method", ref_frame_change_method_, 0);
00079 local_nh.param("ref_frame_motion_threshold", ref_frame_motion_threshold_, 5.0);
00080 local_nh.param("ref_frame_inlier_threshold", ref_frame_inlier_threshold_, 150);
00081
00082 point_cloud_pub_ = local_nh.advertise<PointCloud>("point_cloud", 1);
00083 info_pub_ = local_nh.advertise<VisoInfo>("info", 1);
00084
00085 reference_motion_ = Matrix::eye(4);
00086 }
00087
00088 protected:
00089
00090 void initOdometer(
00091 const sensor_msgs::CameraInfoConstPtr& l_info_msg,
00092 const sensor_msgs::CameraInfoConstPtr& r_info_msg)
00093 {
00094
00095
00096 image_geometry::StereoCameraModel model;
00097 model.fromCameraInfo(*l_info_msg, *r_info_msg);
00098 visual_odometer_params_.base = model.baseline();
00099 visual_odometer_params_.calib.f = model.left().fx();
00100 visual_odometer_params_.calib.cu = model.left().cx();
00101 visual_odometer_params_.calib.cv = model.left().cy();
00102 visual_odometer_.reset(new VisualOdometryStereo(visual_odometer_params_));
00103 if (l_info_msg->header.frame_id != "") setSensorFrameId(l_info_msg->header.frame_id);
00104 updateInitialBaseToSensorTransform();
00105 ROS_INFO_STREAM("Initialized libviso2 stereo odometry "
00106 "with the following parameters:" << std::endl <<
00107 visual_odometer_params_ <<
00108 " ref_frame_change_method = " << ref_frame_change_method_ << std::endl <<
00109 " ref_frame_motion_threshold = " << ref_frame_motion_threshold_ << std::endl <<
00110 " ref_frame_inlier_threshold = " << ref_frame_inlier_threshold_);
00111 }
00112
00113 void imageCallback(
00114 const sensor_msgs::ImageConstPtr& l_image_msg,
00115 const sensor_msgs::ImageConstPtr& r_image_msg,
00116 const sensor_msgs::CameraInfoConstPtr& l_info_msg,
00117 const sensor_msgs::CameraInfoConstPtr& r_info_msg)
00118 {
00119 ros::WallTime start_time = ros::WallTime::now();
00120 bool first_run = false;
00121
00122 if (!visual_odometer_)
00123 {
00124 first_run = true;
00125 initOdometer(l_info_msg, r_info_msg);
00126 }
00127
00128
00129 uint8_t *l_image_data, *r_image_data;
00130 int l_step, r_step;
00131 cv_bridge::CvImageConstPtr l_cv_ptr, r_cv_ptr;
00132 l_cv_ptr = cv_bridge::toCvShare(l_image_msg, sensor_msgs::image_encodings::MONO8);
00133 l_image_data = l_cv_ptr->image.data;
00134 l_step = l_cv_ptr->image.step[0];
00135 r_cv_ptr = cv_bridge::toCvShare(r_image_msg, sensor_msgs::image_encodings::MONO8);
00136 r_image_data = r_cv_ptr->image.data;
00137 r_step = r_cv_ptr->image.step[0];
00138
00139 ROS_ASSERT(l_step == r_step);
00140 ROS_ASSERT(l_image_msg->width == r_image_msg->width);
00141 ROS_ASSERT(l_image_msg->height == r_image_msg->height);
00142
00143 int32_t dims[] = {l_image_msg->width, l_image_msg->height, l_step};
00144
00145
00146 if (first_run || got_lost_)
00147 {
00148 visual_odometer_->process(l_image_data, r_image_data, dims);
00149 got_lost_ = false;
00150
00151 if (first_run)
00152 {
00153 tf::Transform delta_transform;
00154 delta_transform.setIdentity();
00155 integrateAndPublish(delta_transform, l_image_msg->header.stamp);
00156 }
00157 }
00158 else
00159 {
00160 bool success = visual_odometer_->process(
00161 l_image_data, r_image_data, dims, keep_reference_frame_);
00162 if (success)
00163 {
00164 Matrix motion = Matrix::inv(visual_odometer_->getMotion());
00165 ROS_DEBUG("Found %i matches with %i inliers.",
00166 visual_odometer_->getNumberOfMatches(),
00167 visual_odometer_->getNumberOfInliers());
00168 ROS_DEBUG_STREAM("libviso2 returned the following motion:\n" << motion);
00169 Matrix camera_motion;
00170
00171
00172 if (keep_reference_frame_)
00173 {
00174 camera_motion = Matrix::inv(reference_motion_) * motion;
00175 }
00176 else
00177 {
00178
00179 camera_motion = motion;
00180 }
00181 reference_motion_ = motion;
00182
00183 tf::Matrix3x3 rot_mat(
00184 camera_motion.val[0][0], camera_motion.val[0][1], camera_motion.val[0][2],
00185 camera_motion.val[1][0], camera_motion.val[1][1], camera_motion.val[1][2],
00186 camera_motion.val[2][0], camera_motion.val[2][1], camera_motion.val[2][2]);
00187 tf::Vector3 t(camera_motion.val[0][3], camera_motion.val[1][3], camera_motion.val[2][3]);
00188 tf::Transform delta_transform(rot_mat, t);
00189
00190 setPoseCovariance(STANDARD_POSE_COVARIANCE);
00191 setTwistCovariance(STANDARD_TWIST_COVARIANCE);
00192
00193 integrateAndPublish(delta_transform, l_image_msg->header.stamp);
00194
00195 if (point_cloud_pub_.getNumSubscribers() > 0)
00196 {
00197 computeAndPublishPointCloud(l_info_msg, l_image_msg, r_info_msg,
00198 visual_odometer_->getMatches(),
00199 visual_odometer_->getInlierIndices());
00200 }
00201 }
00202 else
00203 {
00204 setPoseCovariance(BAD_COVARIANCE);
00205 setTwistCovariance(BAD_COVARIANCE);
00206 tf::Transform delta_transform;
00207 delta_transform.setIdentity();
00208 integrateAndPublish(delta_transform, l_image_msg->header.stamp);
00209
00210 ROS_DEBUG("Call to VisualOdometryStereo::process() failed.");
00211 ROS_WARN_THROTTLE(1.0, "Visual Odometer got lost!");
00212 got_lost_ = true;
00213 }
00214
00215 if(success)
00216 {
00217
00218
00219 switch ( ref_frame_change_method_ )
00220 {
00221 case REF_FRAME_CHANGE_MOTION:
00222 {
00223
00224 double feature_flow = computeFeatureFlow(visual_odometer_->getMatches());
00225 keep_reference_frame_ = (feature_flow < ref_frame_motion_threshold_);
00226 ROS_DEBUG_STREAM("Feature flow is " << feature_flow
00227 << ", marking last motion as "
00228 << (keep_reference_frame_ ? "small." : "normal."));
00229 break;
00230 }
00231 case REF_FRAME_CHANGE_INLIERS:
00232 {
00233 keep_reference_frame_ = (visual_odometer_->getNumberOfInliers() > ref_frame_inlier_threshold_);
00234 break;
00235 }
00236 default:
00237 keep_reference_frame_ = false;
00238 }
00239
00240 }
00241 else
00242 keep_reference_frame_ = false;
00243
00244 if(!keep_reference_frame_)
00245 ROS_DEBUG_STREAM("Changing reference frame");
00246
00247
00248 VisoInfo info_msg;
00249 info_msg.header.stamp = l_image_msg->header.stamp;
00250 info_msg.got_lost = !success;
00251 info_msg.change_reference_frame = !keep_reference_frame_;
00252 info_msg.num_matches = visual_odometer_->getNumberOfMatches();
00253 info_msg.num_inliers = visual_odometer_->getNumberOfInliers();
00254 ros::WallDuration time_elapsed = ros::WallTime::now() - start_time;
00255 info_msg.runtime = time_elapsed.toSec();
00256 info_pub_.publish(info_msg);
00257 }
00258 }
00259
00260 double computeFeatureFlow(
00261 const std::vector<Matcher::p_match>& matches)
00262 {
00263 double total_flow = 0.0;
00264 for (size_t i = 0; i < matches.size(); ++i)
00265 {
00266 double x_diff = matches[i].u1c - matches[i].u1p;
00267 double y_diff = matches[i].v1c - matches[i].v1p;
00268 total_flow += sqrt(x_diff * x_diff + y_diff * y_diff);
00269 }
00270 return total_flow / matches.size();
00271 }
00272
00273 void computeAndPublishPointCloud(
00274 const sensor_msgs::CameraInfoConstPtr& l_info_msg,
00275 const sensor_msgs::ImageConstPtr& l_image_msg,
00276 const sensor_msgs::CameraInfoConstPtr& r_info_msg,
00277 const std::vector<Matcher::p_match>& matches,
00278 const std::vector<int32_t>& inlier_indices)
00279 {
00280 try
00281 {
00282 cv_bridge::CvImageConstPtr cv_ptr;
00283 cv_ptr = cv_bridge::toCvShare(l_image_msg, sensor_msgs::image_encodings::RGB8);
00284
00285 image_geometry::StereoCameraModel model;
00286 model.fromCameraInfo(*l_info_msg, *r_info_msg);
00287 PointCloud::Ptr point_cloud(new PointCloud());
00288 point_cloud->header.frame_id = getSensorFrameId();
00289 point_cloud->header.stamp = l_info_msg->header.stamp;
00290 point_cloud->width = 1;
00291 point_cloud->height = inlier_indices.size();
00292 point_cloud->points.resize(inlier_indices.size());
00293
00294 for (size_t i = 0; i < inlier_indices.size(); ++i)
00295 {
00296 const Matcher::p_match& match = matches[inlier_indices[i]];
00297 cv::Point2d left_uv;
00298 left_uv.x = match.u1c;
00299 left_uv.y = match.v1c;
00300 cv::Point3d point;
00301 double disparity = match.u1c - match.u2c;
00302 model.projectDisparityTo3d(left_uv, disparity, point);
00303 point_cloud->points[i].x = point.x;
00304 point_cloud->points[i].y = point.y;
00305 point_cloud->points[i].z = point.z;
00306 cv::Vec3b color = cv_ptr->image.at<cv::Vec3b>(left_uv.y,left_uv.x);
00307 point_cloud->points[i].r = color[0];
00308 point_cloud->points[i].g = color[1];
00309 point_cloud->points[i].b = color[2];
00310 }
00311 ROS_DEBUG("Publishing point cloud with %zu points.", point_cloud->size());
00312 point_cloud_pub_.publish(point_cloud);
00313 }
00314 catch (cv_bridge::Exception& e)
00315 {
00316 ROS_ERROR("cv_bridge exception: %s", e.what());
00317 }
00318 }
00319 };
00320
00321 }
00322
00323
00324 int main(int argc, char **argv)
00325 {
00326 ros::init(argc, argv, "stereo_odometer");
00327 if (ros::names::remap("stereo") == "stereo") {
00328 ROS_WARN("'stereo' has not been remapped! Example command-line usage:\n"
00329 "\t$ rosrun viso2_ros stereo_odometer stereo:=narrow_stereo image:=image_rect");
00330 }
00331 if (ros::names::remap("image").find("rect") == std::string::npos) {
00332 ROS_WARN("stereo_odometer needs rectified input images. The used image "
00333 "topic is '%s'. Are you sure the images are rectified?",
00334 ros::names::remap("image").c_str());
00335 }
00336
00337 std::string transport = argc > 1 ? argv[1] : "raw";
00338 viso2_ros::StereoOdometer odometer(transport);
00339
00340 ros::spin();
00341 return 0;
00342 }
00343