|
manif-geom-cpp
|
#include <Eigen/Core>#include <Eigen/Geometry>#include <iostream>#include <math.h>Go to the source code of this file.
Classes | |
| class | SO3< T > |
| Class representing a member of the \(SO(3)\) manifold, or a 3D rotation. More... | |
Typedefs | |
| typedef SO3< double > | SO3d |
Functions | |
| template<typename T > | |
| SO3< T > | operator* (const double &l, const SO3< T > &r) |
| Scale a rotation by a scalar. | |
| template<typename T > | |
| SO3< T > | operator* (const SO3< T > &l, const double &r) |
| Scale a rotation by a scalar. | |
| template<typename T > | |
| std::ostream & | operator<< (std::ostream &os, const SO3< T > &q) |
| Render the rotation in a stream. | |
Scale a rotation by a scalar.
Under the hood, this converts the rotation into a tangent-space vector, scales the vector, then converts the scaled vector back to a rotation.
Scale a rotation by a scalar.
Under the hood, this converts the rotation into a tangent-space vector, scales the vector, then converts the scaled vector back to a rotation.
|
inline |
Render the rotation in a stream.