Namespaces | |
namespace | EulerConventions |
Converts scalar translations and rotations to an Eigen Frame. This is achieved by chaining a translation with individual euler rotations in ZYX order (this is equivalent to fixed rotatins XYZ) http://en.wikipedia.org/wiki/Euler_angles#Conversion_between_intrinsic_and_extrinsic_rotations. | |
Typedefs | |
typedef EulerConventions::EulerConvention | EulerConvention |
Functions | |
static bool | equal (const std::vector< double > &lhs, const std::vector< double > &rhs, const double tol) |
static Eigen::Affine3d | toFrame (double tx, double ty, double tz, double rx, double ry, double rz, int convention=int(EulerConventions::ZYX)) |
static bool descartes_core::utils::equal | ( | const std::vector< double > & | lhs, |
const std::vector< double > & | rhs, | ||
const double | tol | ||
) | [static] |
static Eigen::Affine3d descartes_core::utils::toFrame | ( | double | tx, |
double | ty, | ||
double | tz, | ||
double | rx, | ||
double | ry, | ||
double | rz, | ||
int | convention = int(EulerConventions::ZYX) |
||
) | [static] |