24 using namespace gtsam;
26 #define TEST(TITLE, STATEMENT) \ 27 cout << endl << TITLE << endl; \ 29 for (int i = 0; i < n; i++) STATEMENT; \ 31 seconds = static_cast<double>(timeLog2 - timeLog) / CLOCKS_PER_SEC; \ 32 cout << 1000 * seconds << " milliseconds" << endl; \ 33 cout << (1e9 * seconds / static_cast<double>(n)) << " nanosecs/call" << endl; 37 clock_t timeLog, timeLog2;
40 double norm =
sqrt(1.0 + 16.0 + 4.0);
41 double x = 1.0 / norm,
y = 4.0 / norm,
z = 2.0 / norm;
45 TEST(
"Rodriguez formula given axis angle", Rot3::AxisAngle(v, 0.001))
46 TEST(
"Rodriguez formula given canonical coordinates", Rot3::Rodrigues(v))
51 TEST(
"Slow rotation matrix", Rot3::Rz(z) * Rot3::Ry(y) * Rot3::Rx(x))
52 TEST(
"Fast Rotation matrix", Rot3::RzRyRx(x, y, z))
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
#define TEST(TITLE, STATEMENT)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Class between(const Class &g) const
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
3D rotation represented as a rotation matrix or quaternion
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...