5#ifndef __pinocchio_collision_fcl_convertion_hpp__ 6#define __pinocchio_collision_fcl_convertion_hpp__ 8#include <hpp/fcl/math/transform.h> 9#include "pinocchio/spatial/se3.hpp" 13 template<
typename Scalar>
14 inline hpp::fcl::Transform3f toFclTransform3f(
const SE3Tpl<Scalar> & m)
17 return hpp::fcl::Transform3f(m_.rotation(), m_.translation());
20 inline SE3 toPinocchioSE3(
const hpp::fcl::Transform3f & tf)
22 typedef SE3::Scalar
Scalar;
23 return SE3(tf.getRotation().cast<
Scalar>(), tf.getTranslation().cast<
Scalar>());
Main pinocchio namespace.