libfovis
stereo_rectify.hpp
1 #ifndef __fovis_stereo_rectify_hpp__
2 #define __fovis_stereo_rectify_hpp__
3 
4 #include <Eigen/Core>
5 #include <Eigen/Geometry>
6 
7 #include "camera_intrinsics.hpp"
8 
9 namespace fovis
10 {
11 
12 void
13 stereo_rectify(const CameraIntrinsicsParameters& left_params,
14  const CameraIntrinsicsParameters& right_params,
15  const Eigen::Quaterniond& rotation_quat,
16  const Eigen::Vector3d& translation,
17  Eigen::Matrix3d* left_rotation,
18  Eigen::Matrix3d* right_rotation,
19  CameraIntrinsicsParameters* rectified_params);
20 }
21 
22 #endif
quick and dirty profiling tool.inspired by the matlab tic/toc command
Definition: camera_intrinsics.hpp:6