6 #ifndef __pinocchio_python_spatial_force_hpp__ 7 #define __pinocchio_python_spatial_force_hpp__ 11 #include <boost/python/tuple.hpp> 13 #include "pinocchio/spatial/se3.hpp" 14 #include "pinocchio/spatial/force.hpp" 26 template<
typename T>
struct call;
28 template<
typename Scalar,
int Options>
33 static bool isApprox(
const Force &
self,
const Force & other,
34 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
36 return self.isApprox(other,prec);
39 static bool isZero(
const Force &
self,
40 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
42 return self.isZero(prec);
49 template<
typename Force>
51 :
public boost::python::def_visitor< ForcePythonVisitor<Force> >
62 template<
class PyClass>
66 .def(bp::init<>(bp::arg(
"self"),
"Default constructor"))
67 .def(bp::init<Vector3,Vector3>
68 ((bp::arg(
"self"),bp::arg(
"linear"),bp::arg(
"angular")),
69 "Initialize from linear and angular components of a Wrench vector (don't mix the order)."))
70 .def(bp::init<Vector6>((
bp::args(
"self",
"array")),
"Init from a vector 6 [force,torque]"))
71 .def(bp::init<Force>((
bp::args(
"self",
"other")),
"Copy constructor."))
73 .add_property(
"linear",
74 bp::make_function(&ForcePythonVisitor::getLinear,
75 bp::with_custodian_and_ward_postcall<0,1>()),
76 &ForcePythonVisitor::setLinear,
77 "Linear part of a *this, corresponding to the linear velocity in case of a Spatial velocity.")
78 .add_property(
"angular",
79 bp::make_function(&ForcePythonVisitor::getAngular,
80 bp::with_custodian_and_ward_postcall<0,1>()),
81 &ForcePythonVisitor::setAngular,
82 "Angular part of a *this, corresponding to the angular velocity in case of a Spatial velocity.")
83 .add_property(
"vector",
84 bp::make_function((
typename Force::ToVectorReturnType (Force::*)())&Force::toVector,
85 bp::return_internal_reference<>()),
86 &ForcePythonVisitor::setVector,
87 "Returns the components of *this as a 6d vector.")
89 bp::make_function((
typename Force::ToVectorReturnType (Force::*)())&Force::toVector,
90 bp::return_internal_reference<>()))
92 .def(
"se3Action",&Force::template se3Action<Scalar,Options>,
93 bp::args(
"self",
"M"),
"Returns the result of the dual action of M on *this.")
94 .def(
"se3ActionInverse",&Force::template se3ActionInverse<Scalar,Options>,
95 bp::args(
"self",
"M"),
"Returns the result of the dual action of the inverse of M on *this.")
97 .def(
"setZero",&ForcePythonVisitor::setZero,bp::arg(
"self"),
98 "Set the linear and angular components of *this to zero.")
99 .def(
"setRandom",&ForcePythonVisitor::setRandom,bp::arg(
"self"),
100 "Set the linear and angular components of *this to random values.")
102 .def(bp::self + bp::self)
103 .def(bp::self += bp::self)
104 .def(bp::self - bp::self)
105 .def(bp::self -= bp::self)
108 .def(bp::self == bp::self)
109 .def(bp::self != bp::self)
117 isApproxForce_overload(
bp::args(
"self",
"other",
"prec"),
118 "Returns true if *this is approximately equal to other, within the precision given by prec."))
122 isZero_overload(
bp::args(
"self",
"prec"),
123 "Returns true if *this is approximately equal to the zero Force, within the precision given by prec."))
125 .def(
"Random",&Force::Random,
"Returns a random Force.")
126 .staticmethod(
"Random")
127 .def(
"Zero",&Force::Zero,
"Returns a zero Force.")
128 .staticmethod(
"Zero")
130 .def(
"__array__",bp::make_function((
typename Force::ToVectorReturnType (Force::*)())&Force::toVector,
131 bp::return_internal_reference<>()))
139 bp::class_<Force>(
"Force",
140 "Force vectors, in se3* == F^6.\n\n" 141 "Supported operations ...",
157 {
return bp::make_tuple((Vector3)f.
linear(),(Vector3)f.
angular()); }
160 static RefVector3
getLinear(Force &
self ) {
return self.linear(); }
161 static void setLinear(Force &
self,
const Vector3 & f) {
self.linear(f); }
162 static RefVector3
getAngular(Force &
self) {
return self.angular(); }
163 static void setAngular(Force &
self,
const Vector3 & n) {
self.angular(n); }
165 static void setZero(Force &
self) {
self.setZero(); }
166 static void setRandom(Force &
self) {
self.setRandom(); }
168 static void setVector(Force &
self,
const Vector6 & f) {
self = f; }
174 #endif // ifndef __pinocchio_python_spatial_force_hpp__ static void setZero(Force &self)
void visit(PyClass &cl) const
static bool isZero(const Force &self, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
ForceTpl< Scalar, Options > Force
Set the Python method str and repr to use the overloading operator<<.
BOOST_PYTHON_FUNCTION_OVERLOADS(computeKKTContactDynamicMatrixInverse_overload, computeKKTContactDynamicMatrixInverse_proxy, 4, 5) static const Eigen
ConstAngularType angular() const
Return the angular part of the force vector.
Eigen::Map< Vector3 > MapVector3
Eigen::Ref< Vector3 > RefVector3
static void setRandom(Force &self)
ConstLinearType linear() const
Return the linear part of the force vector.
static RefVector3 getLinear(Force &self)
static void setLinear(Force &self, const Vector3 &f)
static void setVector(Force &self, const Vector6 &f)
Add the Python method copy to allow a copy of this by calling the copy constructor.
static bool isApprox(const Force &self, const Force &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision())
Main pinocchio namespace.
static boost::python::tuple getinitargs(const Force &f)
Common traits structure to fully define base classes for CRTP.
static RefVector3 getAngular(Force &self)
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
static void setAngular(Force &self, const Vector3 &n)