Go to the documentation of this file.00001 #ifndef __fovis_stereo_rectify_hpp__
00002 #define __fovis_stereo_rectify_hpp__
00003
00004 #include <Eigen/Core>
00005 #include <Eigen/Geometry>
00006
00007 #include "camera_intrinsics.hpp"
00008
00009 namespace fovis
00010 {
00011
00012 void
00013 stereo_rectify(const CameraIntrinsicsParameters& left_params,
00014 const CameraIntrinsicsParameters& right_params,
00015 const Eigen::Quaterniond& rotation_quat,
00016 const Eigen::Vector3d& translation,
00017 Eigen::Matrix3d* left_rotation,
00018 Eigen::Matrix3d* right_rotation,
00019 CameraIntrinsicsParameters* rectified_params);
00020 }
00021
00022 #endif