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


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:33