HelloSO3.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include "sophus/geometry.hpp"
3 
4 int main() {
5  // The following demonstrates the group multiplication of rotation matrices
6 
7  // Create rotation matrices from rotations around the x and y and z axes:
8  const double kPi = Sophus::Constants<double>::pi();
9  Sophus::SO3d R1 = Sophus::SO3d::rotX(kPi / 4);
10  Sophus::SO3d R2 = Sophus::SO3d::rotY(kPi / 6);
11  Sophus::SO3d R3 = Sophus::SO3d::rotZ(-kPi / 3);
12 
13  std::cout << "The rotation matrices are" << std::endl;
14  std::cout << "R1:\n" << R1.matrix() << std::endl;
15  std::cout << "R2:\n" << R2.matrix() << std::endl;
16  std::cout << "R3:\n" << R3.matrix() << std::endl;
17  std::cout << "Their product R1*R2*R3:\n"
18  << (R1 * R2 * R3).matrix() << std::endl;
19  std::cout << std::endl;
20 
21  // Rotation matrices can act on vectors
23  x << 0.0, 0.0, 1.0;
24  std::cout << "Rotation matrices can act on vectors" << std::endl;
25  std::cout << "x\n" << x << std::endl;
26  std::cout << "R2*x\n" << R2 * x << std::endl;
27  std::cout << "R1*(R2*x)\n" << R1 * (R2 * x) << std::endl;
28  std::cout << "(R1*R2)*x\n" << (R1 * R2) * x << std::endl;
29  std::cout << std::endl;
30 
31  // SO(3) are internally represented as unit quaternions.
32  std::cout << "R1 in matrix form:\n" << R1.matrix() << std::endl;
33  std::cout << "R1 in unit quaternion form:\n"
34  << R1.unit_quaternion().coeffs() << std::endl;
35  // Note that the order of coefficiences of Eigen's quaternion class is
36  // (imag0, imag1, imag2, real)
37  std::cout << std::endl;
38 }
Sophus::SO3::rotX
static SOPHUS_FUNC SO3 rotX(Scalar const &x)
Definition: so3.hpp:699
Sophus::SO3
SO3 using default storage; derived from SO3Base.
Definition: so3.hpp:19
main
int main()
Definition: HelloSO3.cpp:4
Sophus::Vector3d
Vector3< double > Vector3d
Definition: types.hpp:23
geometry.hpp
Sophus::SO3::rotY
static SOPHUS_FUNC SO3 rotY(Scalar const &y)
Definition: so3.hpp:705
Sophus::Constants::pi
static SOPHUS_FUNC Scalar pi()
Definition: common.hpp:154
Sophus::SO3::rotZ
static SOPHUS_FUNC SO3 rotZ(Scalar const &z)
Definition: so3.hpp:711
Sophus::SO3::unit_quaternion
SOPHUS_FUNC QuaternionMember const & unit_quaternion() const
Definition: so3.hpp:488


sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:47