timeStereoCamera.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
18 #include <time.h>
19 #include <iostream>
20 
22 
23 using namespace std;
24 using namespace gtsam;
25 
26 int main()
27 {
28  int n = 100000;
29 
30  const Pose3 pose1(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5));
31 
32  const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(1500, 1500, 0, 320, 240, 0.5));
33  const StereoCamera camera(pose1, K);
34  const Point3 point1(-0.08,-0.08, 0.0);
35 
36  Matrix computed1, computed2;
37  long timeLog = clock();
38  for(int i = 0; i < n; i++)
39  camera.project(point1, computed1, computed2);
40  long timeLog2 = clock();
41  double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC;
42  cout << ((double)n/seconds) << " calls/second" << endl;
43  cout << ((double)seconds*1000000/n) << " musecs/call" << endl;
44 
45  return 0;
46 }
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
main
int main()
Definition: timeStereoCamera.cpp:26
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Cal3_S2Stereo::shared_ptr
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
gtsam
traits
Definition: SFMdata.h:40
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
pose1
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
K
#define K
Definition: igam.h:8
std
Definition: BFloat16.h:88
gtsam::StereoCamera
Definition: StereoCamera.h:47
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
point1
const Point3 point1(3.0, 4.0, 2.0)
camera
static const CalibratedCamera camera(kDefaultPose)
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::CalibratedCamera::project
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
Definition: CalibratedCamera.cpp:188
StereoCamera.h
A Stereo Camera based on two Simple Cameras.


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:42:30