transform.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019 INRIA
3 //
4 
5 #ifndef __pinocchio_python_collision_fcl_transform_hpp__
6 #define __pinocchio_python_collision_fcl_transform_hpp__
7 
10 
11 namespace boost
12 {
13  namespace python
14  {
15  namespace converter
16  {
17 
18  template<typename Scalar, int Options>
19  struct implicit<::hpp::fcl::Transform3f, ::pinocchio::SE3Tpl<Scalar, Options>>
20  {
21  typedef ::hpp::fcl::Transform3f Source;
22  typedef ::pinocchio::SE3Tpl<Scalar, Options> Target;
23 
24  static void * convertible(PyObject * obj)
25  {
26  // Find a converter which can produce a Source instance from
27  // obj. The user has told us that Source can be converted to
28  // Target, and instantiating construct() below, ensures that
29  // at compile-time.
30  return implicit_rvalue_convertible_from_python(obj, registered<Source>::converters) ? obj
31  : 0;
32  }
33 
34  static void construct(PyObject * obj, rvalue_from_python_stage1_data * data)
35  {
36  void * storage =
37  reinterpret_cast<rvalue_from_python_storage<Target> *>(reinterpret_cast<void *>(data))
38  ->storage.bytes;
39 
40  arg_from_python<Source> get_source(obj);
41  bool convertible = get_source.convertible();
42  BOOST_VERIFY(convertible);
43 
44  const Source & t = get_source();
45  new (storage) Target(t.getRotation(), t.getTranslation());
46 
47  // record successful construction
48  data->convertible = storage;
49  }
50  };
51 
52  template<typename Scalar, int Options>
53  struct implicit<::pinocchio::SE3Tpl<Scalar, Options>, ::hpp::fcl::Transform3f>
54  {
55  typedef ::pinocchio::SE3Tpl<Scalar, Options> Source;
56  typedef ::hpp::fcl::Transform3f Target;
57 
58  static void * convertible(PyObject * obj)
59  {
60  // Find a converter which can produce a Source instance from
61  // obj. The user has told us that Source can be converted to
62  // Target, and instantiating construct() below, ensures that
63  // at compile-time.
64  return implicit_rvalue_convertible_from_python(obj, registered<Source>::converters) ? obj
65  : 0;
66  }
67 
68  static void construct(PyObject * obj, rvalue_from_python_stage1_data * data)
69  {
70  void * storage =
71  reinterpret_cast<rvalue_from_python_storage<Target> *>(reinterpret_cast<void *>(data))
72  ->storage.bytes;
73 
74  arg_from_python<Source> get_source(obj);
75  bool convertible = get_source.convertible();
76  BOOST_VERIFY(convertible);
77 
78  const Source & M = get_source();
79  new (storage) Target(M.rotation(), M.translation());
80 
81  // record successful construction
82  data->convertible = storage;
83  }
84  };
85 
86  } // namespace converter
87  } // namespace python
88 } // namespace boost
89 
90 #endif // ifndef __pinocchio_python_collision_fcl_transform_hpp__
boost::python::converter::implicit<::hpp::fcl::Transform3f, ::pinocchio::SE3Tpl< Scalar, Options > >::convertible
static void * convertible(PyObject *obj)
Definition: transform.hpp:24
boost::python::converter::implicit<::pinocchio::SE3Tpl< Scalar, Options >, ::hpp::fcl::Transform3f >::Source
::pinocchio::SE3Tpl< Scalar, Options > Source
Definition: transform.hpp:55
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
transform.h
setup.data
data
Definition: cmake/cython/setup.in.py:48
boost::python::converter::implicit<::hpp::fcl::Transform3f, ::pinocchio::SE3Tpl< Scalar, Options > >::construct
static void construct(PyObject *obj, rvalue_from_python_stage1_data *data)
Definition: transform.hpp:34
boost::python::converter::implicit<::pinocchio::SE3Tpl< Scalar, Options >, ::hpp::fcl::Transform3f >::convertible
static void * convertible(PyObject *obj)
Definition: transform.hpp:58
boost
python
se3.hpp
boost::python::converter::implicit<::hpp::fcl::Transform3f, ::pinocchio::SE3Tpl< Scalar, Options > >::Source
::hpp::fcl::Transform3f Source
Definition: transform.hpp:21
M
M
boost::python::converter::implicit<::hpp::fcl::Transform3f, ::pinocchio::SE3Tpl< Scalar, Options > >::Target
::pinocchio::SE3Tpl< Scalar, Options > Target
Definition: transform.hpp:22
hpp::fcl::Transform3f
t
Transform3f t
boost::python::converter::implicit<::pinocchio::SE3Tpl< Scalar, Options >, ::hpp::fcl::Transform3f >::construct
static void construct(PyObject *obj, rvalue_from_python_stage1_data *data)
Definition: transform.hpp:68
boost::python::converter::implicit<::pinocchio::SE3Tpl< Scalar, Options >, ::hpp::fcl::Transform3f >::Target
::hpp::fcl::Transform3f Target
Definition: transform.hpp:56


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:41