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