collision/fcl-pinocchio-conversions.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_collision_fcl_convertion_hpp__
6 #define __pinocchio_collision_fcl_convertion_hpp__
7 
10 
11 namespace pinocchio
12 {
13  template<typename Scalar>
15  {
16  SE3Tpl<double, 0> m_ = m.template cast<double>();
17  return hpp::fcl::Transform3f(m_.rotation(), m_.translation());
18  }
19 
21  {
22  typedef SE3::Scalar Scalar;
23  return SE3(tf.getRotation().cast<Scalar>(), tf.getTranslation().cast<Scalar>());
24  }
25 
26 } // namespace pinocchio
27 
28 #endif // ifndef __pinocchio_collision_fcl_convertion_hpp__
test-cpp2pybind11.m
m
Definition: test-cpp2pybind11.py:25
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
transform.h
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::SE3Tpl::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::toFclTransform3f
hpp::fcl::Transform3f toFclTransform3f(const SE3Tpl< Scalar > &m)
Definition: collision/fcl-pinocchio-conversions.hpp:14
se3.hpp
pinocchio::SE3Tpl::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
pinocchio::toPinocchioSE3
SE3 toPinocchioSE3(const hpp::fcl::Transform3f &tf)
Definition: collision/fcl-pinocchio-conversions.hpp:20
hpp::fcl::Transform3f::getTranslation
const Vec3f & getTranslation() const
hpp::fcl::Transform3f::getRotation
const Matrix3f & getRotation() const
hpp::fcl::Transform3f
pinocchio::SE3
SE3Tpl< context::Scalar, context::Options > SE3
Definition: spatial/fwd.hpp:64
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:01