5 #ifndef __pinocchio_python_collision_fcl_transform_hpp__
6 #define __pinocchio_python_collision_fcl_transform_hpp__
18 template<
typename Scalar,
int Options>
21 typedef ::hpp::fcl::Transform3f
Source;
22 typedef ::pinocchio::SE3Tpl<Scalar, Options>
Target;
30 return implicit_rvalue_convertible_from_python(obj, registered<Source>::converters) ? obj
34 static void construct(PyObject * obj, rvalue_from_python_stage1_data *
data)
37 reinterpret_cast<rvalue_from_python_storage<Target> *
>(
reinterpret_cast<void *
>(
data))
40 arg_from_python<Source> get_source(obj);
41 bool convertible = get_source.convertible();
42 BOOST_VERIFY(convertible);
44 const Source &
t = get_source();
45 new (storage)
Target(
t.getRotation(),
t.getTranslation());
48 data->convertible = storage;
52 template<
typename Scalar,
int Options>
55 typedef ::pinocchio::SE3Tpl<Scalar, Options>
Source;
56 typedef ::hpp::fcl::Transform3f
Target;
64 return implicit_rvalue_convertible_from_python(obj, registered<Source>::converters) ? obj
68 static void construct(PyObject * obj, rvalue_from_python_stage1_data *
data)
71 reinterpret_cast<rvalue_from_python_storage<Target> *
>(
reinterpret_cast<void *
>(
data))
74 arg_from_python<Source> get_source(obj);
75 bool convertible = get_source.convertible();
76 BOOST_VERIFY(convertible);
78 const Source &
M = get_source();
79 new (storage)
Target(
M.rotation(),
M.translation());
82 data->convertible = storage;
90 #endif // ifndef __pinocchio_python_collision_fcl_transform_hpp__