38 #ifndef AMINO_RX_SCENE_FCL_H
39 #define AMINO_RX_SCENE_FCL_H
52 #include "amino/eigen_compat.hpp"
57 typedef double fcl_scalar;
59 typedef ::fcl::CollisionGeometry<fcl_scalar> CollisionGeometry ;
60 typedef ::fcl::CollisionObject<fcl_scalar> CollisionObject ;
61 typedef ::fcl::Vector3<fcl_scalar> Vec3;
62 typedef ::fcl::OBBRSS<fcl_scalar> OBBRSS;
64 typedef ::fcl::Box<fcl_scalar> Box;
65 typedef ::fcl::Sphere<fcl_scalar> Sphere;
66 typedef ::fcl::Cylinder<fcl_scalar> Cylinder;
68 typedef ::fcl::CollisionRequest<fcl_scalar> CollisionRequest;
69 typedef ::fcl::CollisionResult<fcl_scalar> CollisionResult;
70 typedef ::fcl::Contact<fcl_scalar> Contact;
71 typedef ::fcl::BroadPhaseCollisionManager<fcl_scalar> BroadPhaseCollisionManager;
72 typedef ::fcl::DynamicAABBTreeCollisionManager<fcl_scalar> DynamicAABBTreeCollisionManager;
74 typedef ::fcl::DistanceRequest<fcl_scalar> DistanceRequest;
75 typedef ::fcl::DistanceResult<fcl_scalar> DistanceResult;
79 static inline ::fcl::Transform3<::amino::fcl::fcl_scalar>
80 qutr2fcltf(
const double E[7] )
86 ::fcl::Transform3<::amino::fcl::fcl_scalar> result;
87 ::amino::conv(&oE, &result);
#define AA_TF_QUTR_V
Offset of translation part in quaternion-translation representation.
#define AA_TF_QUTR_Q
Offset of quaternion part in quaternion-translation representation.
A rotation quaternion and translation vector object.
static aa_tf_qv from_qv(const double a_r[4], const double a_v[3])
Create a quaternion-translation from a rotation quaternion and a translation vector.
Include this file for low-level operations for SE(3) orientations and transformations.