Go to the documentation of this file.
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))
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
#define TEST(TITLE, STATEMENT)
3D rotation represented as a rotation matrix or quaternion
Pose2_ Expmap(const Vector3_ &xi)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Array< int, Dynamic, 1 > v
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Jet< T, N > sqrt(const Jet< T, N > &f)
Rot2 R(Rot2::fromAngle(0.1))
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:09:01