bindings/python/spatial/motion.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_python_spatial_motion_hpp__
7 #define __pinocchio_python_spatial_motion_hpp__
8 
9 #include <eigenpy/eigenpy.hpp>
10 #include <eigenpy/memory.hpp>
11 #include <boost/python/tuple.hpp>
12 #include <boost/python/implicit.hpp>
13 
17 
21 
22 #if EIGENPY_VERSION_AT_MOST(2, 8, 1)
24 #endif
25 
26 namespace pinocchio
27 {
28  namespace python
29  {
30  namespace bp = boost::python;
31 
32  template<typename T>
33  struct call;
34 
35  template<typename Scalar, int Options>
37  {
39 
40  static bool isApprox(
41  const Motion & self,
42  const Motion & other,
43  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
44  {
45  return self.isApprox(other, prec);
46  }
47 
48  static bool
49  isZero(const Motion & self, const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
50  {
51  return self.isZero(prec);
52  }
53  };
54 
55  template<typename Motion>
56  struct MotionPythonVisitor : public boost::python::def_visitor<MotionPythonVisitor<Motion>>
57  {
58  enum
59  {
61  };
62 
63  typedef typename Motion::Scalar Scalar;
65  typedef typename Motion::Vector6 Vector6;
66  typedef typename Motion::Vector3 Vector3;
67 
68  typedef typename Eigen::Map<Vector3> MapVector3;
69  typedef typename Eigen::Ref<Vector3> RefVector3;
70 
71  public:
72  template<class PyClass>
73  void visit(PyClass & cl) const
74  {
75  static const Scalar dummy_precision = Eigen::NumTraits<Scalar>::dummy_precision();
78  cl.def(bp::init<>(bp::arg("self"), "Default constructor"))
79  .def(bp::init<const Vector3 &, const Vector3 &>(
80  (bp::arg("self"), bp::arg("linear"), bp::arg("angular")),
81  "Initialize from linear and angular components of a Motion vector (don't mix the "
82  "order)."))
83  .def(bp::init<const Vector6 &>(
84  (bp::arg("self"), bp::arg("array")),
85  "Init from a vector 6 [linear velocity, angular velocity]"))
86  .def(bp::init<const Motion &>((bp::arg("self"), bp::arg("clone")), "Copy constructor"))
87 
88  .add_property(
89  "linear",
90  bp::make_function(
91  &MotionPythonVisitor::getLinear, bp::with_custodian_and_ward_postcall<0, 1>()),
93  "Linear part of a *this, corresponding to the linear velocity in case of a "
94  "Spatial velocity.")
95  .add_property(
96  "angular",
97  bp::make_function(
98  &MotionPythonVisitor::getAngular, bp::with_custodian_and_ward_postcall<0, 1>()),
100  "Angular part of a *this, corresponding to the angular velocity in case of "
101  "a Spatial velocity.")
102  .add_property(
103  "vector",
104  bp::make_function(
105  (typename Motion::ToVectorReturnType(Motion::*)()) & Motion::toVector,
106  bp::return_internal_reference<>()),
107  &MotionPythonVisitor::setVector, "Returns the components of *this as a 6d vector.")
108  .add_property(
109  "np", bp::make_function(
110  (typename Motion::ToVectorReturnType(Motion::*)()) & Motion::toVector,
111  bp::return_internal_reference<>()))
112 
113  .def(
114  "se3Action", &Motion::template se3Action<Scalar, Options>, bp::args("self", "M"),
115  "Returns the result of the action of M on *this.")
116  .def(
117  "se3ActionInverse", &Motion::template se3ActionInverse<Scalar, Options>,
118  bp::args("self", "M"), "Returns the result of the action of the inverse of M on *this.")
119 
120  .add_property(
121  "action", &Motion::toActionMatrix,
122  "Returns the action matrix of *this (acting on Motion).")
123  .add_property(
124  "dualAction", &Motion::toDualActionMatrix,
125  "Returns the dual action matrix of *this (acting on Force).")
126  .add_property(
127  "homogeneous", &Motion::toHomogeneousMatrix,
128  "Equivalent homogeneous representation of the Motion vector")
129 
130  .def(
131  "setZero", &MotionPythonVisitor::setZero, bp::arg("self"),
132  "Set the linear and angular components of *this to zero.")
133  .def(
134  "setRandom", &MotionPythonVisitor::setRandom, bp::arg("self"),
135  "Set the linear and angular components of *this to random values.")
136 
137  .def(
138  "dot", (Scalar(Motion::*)(const ForceBase<Force> &) const)&Motion::dot,
139  bp::args("self", "f"), "Dot product between *this and a Force f.")
140 
141  .def(
142  "cross", (Motion(Motion::*)(const Motion &) const)&Motion::cross, bp::args("self", "m"),
143  "Action of *this onto another Motion m. Returns ยจ*this x m.")
144  .def(
145  "cross", (Force(Motion::*)(const Force &) const)&Motion::cross, bp::args("self", "f"),
146  "Dual action of *this onto a Force f. Returns *this x* f.")
147 
148  .def(bp::self + bp::self)
149  .def(bp::self += bp::self)
150  .def(bp::self - bp::self)
151  .def(bp::self -= bp::self)
152  .def(-bp::self)
153  .def(bp::self ^ bp::self)
154  .def(bp::self ^ Force())
155 
156 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
157  .def(bp::self == bp::self)
158  .def(bp::self != bp::self)
159 #endif
160 
161  .def(bp::self * Scalar())
162  .def(Scalar() * bp::self)
163  .def(bp::self / Scalar())
164 
165 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
166  .def(
167  "isApprox", &call<Motion>::isApprox,
168  (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision),
169  "Returns true if *this is approximately equal to other, within the precision given "
170  "by prec.")
171 
172  .def(
173  "isZero", &call<Motion>::isZero, (bp::arg("self"), bp::arg("prec") = dummy_precision),
174  "Returns true if *this is approximately equal to the zero Motion, within the "
175  "precision given by prec.")
176 #endif
177 
178  .def("Random", &Motion::Random, "Returns a random Motion.")
179  .staticmethod("Random")
180  .def("Zero", &Motion::Zero, "Returns a zero Motion.")
181  .staticmethod("Zero")
182 
183  .def(
184  "__array__", bp::make_function(
185  (typename Motion::ToVectorReturnType(Motion::*)()) & Motion::toVector,
186  bp::return_internal_reference<>()))
187  .def(
188  "__array__", &__array__,
189  (bp::arg("self"), bp::arg("dtype") = bp::object(), bp::arg("copy") = bp::object()),
190  bp::return_internal_reference<>())
191 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
192  .def_pickle(Pickle())
193 #endif
194  ;
196  }
197 
198  static void expose()
199  {
201  bp::objects::register_dynamic_id<MotionBase>();
202  bp::objects::register_conversion<Motion, MotionBase>(false);
203 
205  bp::objects::register_dynamic_id<MotionDense>();
206  bp::objects::register_conversion<Motion, MotionDense>(false);
207 
208 #if PY_MAJOR_VERSION == 3 && PY_MINOR_VERSION == 6 && EIGENPY_VERSION_AT_LEAST(2, 9, 0)
209  typedef PINOCCHIO_SHARED_PTR_HOLDER_TYPE(Motion) HolderType;
210 #else
211  typedef ::boost::python::detail::not_specified HolderType;
212 #endif
213  bp::class_<Motion, HolderType>(
214  "Motion",
215  "Motion vectors, in se3 == M^6.\n\n"
216  "Supported operations ...",
217  bp::no_init)
219  .def(CastVisitor<Motion>())
222  .def(PrintableVisitor<Motion>());
223  }
224 
225  private:
226  static typename Motion::ToVectorConstReturnType
227  __array__(const Motion & self, bp::object, bp::object)
228  {
229  return self.toVector();
230  }
231 
232  struct Pickle : bp::pickle_suite
233  {
234  static boost::python::tuple getinitargs(const Motion & m)
235  {
236  return bp::make_tuple((Vector3)m.linear(), (Vector3)m.angular());
237  }
238 
239  static bool getstate_manages_dict()
240  {
241  return true;
242  }
243  };
244 
245  static RefVector3 getLinear(Motion & self)
246  {
247  return self.linear();
248  }
249  static void setLinear(Motion & self, const Vector3 & v)
250  {
251  self.linear(v);
252  }
253  static RefVector3 getAngular(Motion & self)
254  {
255  return self.angular();
256  }
257  static void setAngular(Motion & self, const Vector3 & w)
258  {
259  self.angular(w);
260  }
261 
262  static void setVector(Motion & self, const Vector6 & v)
263  {
264  self = v;
265  }
266 
267  static void setZero(Motion & self)
268  {
269  self.setZero();
270  }
271  static void setRandom(Motion & self)
272  {
273  self.setRandom();
274  }
275  };
276 
277  } // namespace python
278 } // namespace pinocchio
279 
280 #endif // ifndef __pinocchio_python_spatial_motion_hpp__
pinocchio::python::MotionPythonVisitor::setZero
static void setZero(Motion &self)
Definition: bindings/python/spatial/motion.hpp:267
boost::python
test-cpp2pybind11.m
m
Definition: test-cpp2pybind11.py:25
PINOCCHIO_SHARED_PTR_HOLDER_TYPE
#define PINOCCHIO_SHARED_PTR_HOLDER_TYPE(T)
Definition: bindings/python/fwd.hpp:17
pinocchio::python::MotionPythonVisitor::Scalar
Motion::Scalar Scalar
Definition: bindings/python/spatial/motion.hpp:63
eigenpy.hpp
pinocchio::python::MotionPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/spatial/motion.hpp:73
pinocchio::python::MotionPythonVisitor
Definition: bindings/python/spatial/motion.hpp:56
pinocchio::python::MotionPythonVisitor::Vector3
Motion::Vector3 Vector3
Definition: bindings/python/spatial/motion.hpp:66
pinocchio::ForceBase
Base interface for forces representation.
Definition: context/casadi.hpp:32
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_SELF_ASSIGN_OVERLOADED
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_SELF_ASSIGN_OVERLOADED
Definition: include/pinocchio/macros.hpp:133
pinocchio::python::ExposeConstructorByCastVisitor
Definition: bindings/python/utils/cast.hpp:33
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Definition: include/pinocchio/macros.hpp:130
pinocchio::MotionDense
Definition: context/casadi.hpp:36
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::python::MotionPythonVisitor::setVector
static void setVector(Motion &self, const Vector6 &v)
Definition: bindings/python/spatial/motion.hpp:262
motion.hpp
pinocchio::MotionBase
Definition: spatial/fwd.hpp:42
pinocchio::python::MotionPythonVisitor::Force
ForceTpl< Scalar, Options > Force
Definition: bindings/python/spatial/motion.hpp:64
pinocchio::python::call< MotionTpl< Scalar, Options > >::isApprox
static bool isApprox(const Motion &self, const Motion &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
Definition: bindings/python/spatial/motion.hpp:40
pinocchio::python::call
Definition: bindings/python/spatial/force.hpp:31
pinocchio::python::MotionPythonVisitor::setRandom
static void setRandom(Motion &self)
Definition: bindings/python/spatial/motion.hpp:271
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
pinocchio::python::MotionPythonVisitor::MapVector3
Eigen::Map< Vector3 > MapVector3
Definition: bindings/python/spatial/motion.hpp:68
cast.hpp
EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
pinocchio::python::MotionPythonVisitor::RefVector3
Eigen::Ref< Vector3 > RefVector3
Definition: bindings/python/spatial/motion.hpp:69
pinocchio::python::PrintableVisitor
Set the Python method str and repr to use the overloading operator<<.
Definition: printable.hpp:21
pinocchio::python::MotionPythonVisitor::expose
static void expose()
Definition: bindings/python/spatial/motion.hpp:198
pinocchio::python::MotionPythonVisitor::Options
@ Options
Definition: bindings/python/spatial/motion.hpp:60
python
se3.hpp
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::ForceTpl< Scalar, Options >
pinocchio::python::CopyableVisitor
Add the Python method copy to allow a copy of this by calling the copy constructor.
Definition: copyable.hpp:21
pinocchio::python::MotionPythonVisitor::Pickle::getinitargs
static boost::python::tuple getinitargs(const Motion &m)
Definition: bindings/python/spatial/motion.hpp:234
pinocchio::python::MotionPythonVisitor::getAngular
static RefVector3 getAngular(Motion &self)
Definition: bindings/python/spatial/motion.hpp:253
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
Definition: include/pinocchio/macros.hpp:129
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
ur5x4.w
w
Definition: ur5x4.py:50
pinocchio::python::CastVisitor
Add the Python method cast.
Definition: bindings/python/utils/cast.hpp:23
copyable.hpp
pinocchio::MotionTpl::Random
static MotionTpl Random()
Definition: motion-tpl.hpp:140
pinocchio::Motion
MotionTpl<::CppAD::AD< double >, 0 > Motion
Definition: context/cppad.hpp:37
pinocchio::python::MotionPythonVisitor::setAngular
static void setAngular(Motion &self, const Vector3 &w)
Definition: bindings/python/spatial/motion.hpp:257
pinocchio::python::MotionPythonVisitor::Pickle
Definition: bindings/python/spatial/motion.hpp:232
pinocchio::python::MotionPythonVisitor::Vector6
Motion::Vector6 Vector6
Definition: bindings/python/spatial/motion.hpp:65
pinocchio::MotionTpl::Zero
static MotionTpl Zero()
Definition: motion-tpl.hpp:136
cl
cl
pinocchio::cross
void cross(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout)
Applies the cross product onto the columns of M.
Definition: skew.hpp:228
pinocchio::python::internal::call
auto call(R(*f)(Args...), typename convert_type< Args >::type... args)
Definition: pybind11.hpp:137
memory.hpp
printable.hpp
pinocchio::python::MotionPythonVisitor::Pickle::getstate_manages_dict
static bool getstate_manages_dict()
Definition: bindings/python/spatial/motion.hpp:239
pinocchio::traits
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:71
pinocchio::MotionTpl
Definition: context/casadi.hpp:27
pinocchio::python::MotionPythonVisitor::setLinear
static void setLinear(Motion &self, const Vector3 &v)
Definition: bindings/python/spatial/motion.hpp:249
pinocchio::python::MotionPythonVisitor::getLinear
static RefVector3 getLinear(Motion &self)
Definition: bindings/python/spatial/motion.hpp:245
force.hpp
pinocchio::python::call< MotionTpl< Scalar, Options > >::isZero
static bool isZero(const Motion &self, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
Definition: bindings/python/spatial/motion.hpp:49
pinocchio::python::MotionPythonVisitor::__array__
static Motion::ToVectorConstReturnType __array__(const Motion &self, bp::object, bp::object)
Definition: bindings/python/spatial/motion.hpp:227
pinocchio::python::call< MotionTpl< Scalar, Options > >::Motion
MotionTpl< Scalar, Options > Motion
Definition: bindings/python/spatial/motion.hpp:38
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:12