4#ifndef __multicontact_api_python_scenario_contact_patch_hpp__
5#define __multicontact_api_python_scenario_contact_patch_hpp__
16namespace bp = boost::python;
18template <
typename ContactPatch>
20 :
public boost::python::def_visitor<
21 ContactPatchPythonVisitor<ContactPatch> > {
22 typedef typename ContactPatch::Scalar
Scalar;
23 typedef typename ContactPatch::SE3
SE3;
26 template <
class PyClass>
28 cl.def(bp::init<>(bp::arg(
""),
"Default constructor."))
30 bp::init<SE3>(bp::arg(
"placement"),
"Init with a given placement."))
31 .def(bp::init<SE3, Scalar>(
32 bp::args(
"placement",
"friction"),
33 "Init with a given placement and friction coefficient."))
34 .def(bp::init<SE3, ContactModel>(
35 bp::args(
"placement",
"contact_model"),
36 "Init with a given placement and contact model."))
37 .def(bp::init<ContactPatch>(bp::arg(
"other"),
"Copy contructor."))
42 bp::make_function(&
getPlacement, bp::return_internal_reference<>()),
44 "Placement of the patch represented as a pinocchio SE3 object.")
46 "Friction coefficient between the robot and the "
47 "environment for this contact.")
48 .def_readwrite(
"contact_model", &ContactPatch::m_contact_model,
49 "The contact model defining this contact.")
50 .def(bp::self == bp::self)
51 .def(bp::self != bp::self)
52 .def(
"copy", &
copy,
"Returns a copy of *this.");
55 static void expose(
const std::string& class_name) {
56 std::string doc =
"Contact Patch";
57 bp::class_<ContactPatch>(class_name.c_str(), doc.c_str(), bp::no_init)
67 self.placement() = placement;
71 self.friction() = friction;
73 static ContactPatch
copy(
const ContactPatch& self) {
74 return ContactPatch(self);