38 #ifndef AMINO_RX_SCENE_FCL_H
39 #define AMINO_RX_SCENE_FCL_H
49 #include <fcl/math/transform.h>
55 static inline ::fcl::Transform3f
56 qutr2fcltf(
const double E[7] )
59 const double *v = E + AA_TF_QUTR_V;
60 return ::fcl::Transform3f(::fcl::Quaternion3f( q[
AA_TF_QUAT_W],
64 ::fcl::Vec3f(v[0], v[1], v[2]));
#define AA_TF_QUAT_Z
Index of quaternion vector z.
#define AA_TF_QUTR_Q
Index of quaternion-translation quaternion part.
#define AA_TF_QUAT_Y
Index of quaternion vector y.
#define AA_TF_QUAT_X
Index of quaternion vector x.
#define AA_TF_QUAT_W
Index of quaternion scalar part.