24 using namespace gtsam;
42 Matrix computed1, computed2;
43 long timeLog = clock();
44 for(
int i = 0;
i <
n;
i++)
45 camera.
project(point1, computed1, computed2);
46 long timeLog2 = clock();
47 double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC;
48 cout << ((double)n/seconds) <<
" calls/second" << endl;
49 cout << ((double)seconds*1000000/n) <<
" musecs/call" << endl;
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Calibrated camera for which only pose is unknown.
const Point3 point1(3.0, 4.0, 2.0)
static const CalibratedCamera camera(kDefaultPose)
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const