6 #ifndef __pinocchio_python_spatial_motion_hpp__ 7 #define __pinocchio_python_spatial_motion_hpp__ 11 #include <boost/python/tuple.hpp> 13 #include "pinocchio/spatial/se3.hpp" 14 #include "pinocchio/spatial/motion.hpp" 15 #include "pinocchio/spatial/force.hpp" 27 template<
typename T>
struct call;
29 template<
typename Scalar,
int Options>
34 static bool isApprox(
const Motion &
self,
const Motion & other,
35 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
37 return self.isApprox(other,prec);
40 static bool isZero(
const Motion &
self,
41 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
43 return self.isZero(prec);
50 template<
typename Motion>
52 :
public boost::python::def_visitor< MotionPythonVisitor<Motion> >
66 template<
class PyClass>
70 .def(bp::init<>(bp::arg(
"self"),
"Default constructor"))
71 .def(bp::init<Vector3,Vector3>
72 ((bp::arg(
"self"),bp::arg(
"linear"),bp::arg(
"angular")),
73 "Initialize from linear and angular components of a Motion vector (don't mix the order)."))
74 .def(bp::init<Vector6>((bp::arg(
"self"),bp::arg(
"array")),
"Init from a vector 6 [linear velocity, angular velocity]"))
75 .def(bp::init<Motion>((bp::arg(
"self"),bp::arg(
"other")),
"Copy constructor."))
77 .add_property(
"linear",
78 bp::make_function(&MotionPythonVisitor::getLinear,
79 bp::with_custodian_and_ward_postcall<0,1>()),
80 &MotionPythonVisitor::setLinear,
81 "Linear part of a *this, corresponding to the linear velocity in case of a Spatial velocity.")
82 .add_property(
"angular",
83 bp::make_function(&MotionPythonVisitor::getAngular,
84 bp::with_custodian_and_ward_postcall<0,1>()),
85 &MotionPythonVisitor::setAngular,
86 "Angular part of a *this, corresponding to the angular velocity in case of a Spatial velocity.")
87 .add_property(
"vector",
88 bp::make_function((
typename Motion::ToVectorReturnType (Motion::*)())&Motion::toVector,
89 bp::return_internal_reference<>()),
90 &MotionPythonVisitor::setVector,
91 "Returns the components of *this as a 6d vector.")
93 bp::make_function((
typename Motion::ToVectorReturnType (Motion::*)())&Motion::toVector,
94 bp::return_internal_reference<>()))
96 .def(
"se3Action",&Motion::template se3Action<Scalar,Options>,
97 bp::args(
"self",
"M"),
"Returns the result of the action of M on *this.")
98 .def(
"se3ActionInverse",&Motion::template se3ActionInverse<Scalar,Options>,
99 bp::args(
"self",
"M"),
"Returns the result of the action of the inverse of M on *this.")
101 .add_property(
"action",&Motion::toActionMatrix,
"Returns the action matrix of *this (acting on Motion).")
102 .add_property(
"dualAction",&Motion::toDualActionMatrix,
"Returns the dual action matrix of *this (acting on Force).")
104 .def(
"setZero",&MotionPythonVisitor::setZero,bp::arg(
"self"),
105 "Set the linear and angular components of *this to zero.")
106 .def(
"setRandom",&MotionPythonVisitor::setRandom,bp::arg(
"self"),
107 "Set the linear and angular components of *this to random values.")
109 .def(
"cross",(Motion (Motion::*)(
const Motion &)
const) &
Motion::cross,
110 bp::args(
"self",
"m"),
"Action of *this onto another Motion m. Returns ยจ*this x m.")
111 .def(
"cross",(Force (Motion::*)(
const Force &)
const) &Motion::cross,
112 bp::args(
"self",
"f"),
"Dual action of *this onto a Force f. Returns *this x* f.")
114 .def(bp::self + bp::self)
115 .def(bp::self += bp::self)
116 .def(bp::self - bp::self)
117 .def(bp::self -= bp::self)
119 .def(bp::self ^ bp::self)
120 .def(bp::self ^
Force())
122 .def(bp::self == bp::self)
123 .def(bp::self != bp::self)
131 isApproxMotion_overload(
bp::args(
"self",
"other",
"prec"),
132 "Returns true if *this is approximately equal to other, within the precision given by prec."))
136 isZero_overload(
bp::args(
"self",
"prec"),
137 "Returns true if *this is approximately equal to the zero Motion, within the precision given by prec."))
139 .def(
"Random",&Motion::Random,
"Returns a random Motion.")
140 .staticmethod(
"Random")
141 .def(
"Zero",&Motion::Zero,
"Returns a zero Motion.")
142 .staticmethod(
"Zero")
144 .def(
"__array__",bp::make_function((
typename Motion::ToVectorReturnType (Motion::*)())&Motion::toVector,
145 bp::return_internal_reference<>()))
153 bp::class_<Motion>(
"Motion",
154 "Motion vectors, in se3 == M^6.\n\n" 155 "Supported operations ...",
170 {
return bp::make_tuple((Vector3)m.
linear(),(Vector3)m.
angular()); }
173 static RefVector3
getLinear(Motion &
self) {
return self.linear(); }
174 static void setLinear (Motion &
self,
const Vector3 & v) {
self.linear(v); }
175 static RefVector3
getAngular(Motion &
self) {
return self.angular(); }
176 static void setAngular(Motion &
self,
const Vector3 &
w) {
self.angular(w); }
178 static void setVector(Motion &
self,
const Vector6 & v) {
self = v; }
180 static void setZero(Motion &
self) {
self.setZero(); }
181 static void setRandom(Motion &
self) {
self.setRandom(); }
187 #endif // ifndef __pinocchio_python_spatial_motion_hpp__
ForceTpl< double, 0 > Force
static bool isZero(const Motion &self, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
Set the Python method str and repr to use the overloading operator<<.
static void setZero(Motion &self)
BOOST_PYTHON_FUNCTION_OVERLOADS(computeKKTContactDynamicMatrixInverse_overload, computeKKTContactDynamicMatrixInverse_proxy, 4, 5) static const Eigen
Eigen::Ref< Vector3 > RefVector3
static void setLinear(Motion &self, const Vector3 &v)
static void setAngular(Motion &self, const Vector3 &w)
MotionTpl< Scalar, Options > Motion
ConstLinearType linear() const
static RefVector3 getLinear(Motion &self)
static boost::python::tuple getinitargs(const Motion &m)
Add the Python method copy to allow a copy of this by calling the copy constructor.
Main pinocchio namespace.
static void setVector(Motion &self, const Vector6 &v)
static RefVector3 getAngular(Motion &self)
Eigen::Map< Vector3 > MapVector3
Common traits structure to fully define base classes for CRTP.
static bool isApprox(const Motion &self, const Motion &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
ConstAngularType angular() const
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
ForceTpl< Scalar, traits< Motion >::Options > Force
void visit(PyClass &cl) const
static void setRandom(Motion &self)