Loading...
Searching...
No Matches
contact-patch.hpp
Go to the documentation of this file.
1// Copyright (c) 2015-2018, CNRS
2// Authors: Justin Carpentier <jcarpent@laas.fr>
3
4#ifndef __multicontact_api_python_scenario_contact_patch_hpp__
5#define __multicontact_api_python_scenario_contact_patch_hpp__
6
7#include <string>
8
12
13namespace multicontact_api {
14namespace python {
15
16namespace bp = boost::python;
17
18template <typename ContactPatch>
20 : public boost::python::def_visitor<
21 ContactPatchPythonVisitor<ContactPatch> > {
22 typedef typename ContactPatch::Scalar Scalar;
23 typedef typename ContactPatch::SE3 SE3;
24 typedef typename ContactPatch::ContactModel ContactModel;
25
26 template <class PyClass>
27 void visit(PyClass& cl) const {
28 cl.def(bp::init<>(bp::arg(""), "Default constructor."))
29 .def(
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."))
38 .add_property(
39 "placement",
40 // getter require to use "make_function" to pass the
41 // return_internal_reference policy (return ref to custom object)
42 bp::make_function(&getPlacement, bp::return_internal_reference<>()),
44 "Placement of the patch represented as a pinocchio SE3 object.")
45 .add_property("friction", &getFriction, &setFriction,
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.");
53 }
54
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)
61 }
62
63 protected:
64 // define setter and getter
65 static SE3& getPlacement(ContactPatch& self) { return self.placement(); }
66 static void setPlacement(ContactPatch& self, const SE3& placement) {
67 self.placement() = placement;
68 }
69 static Scalar getFriction(ContactPatch& self) { return self.friction(); }
70 static void setFriction(ContactPatch& self, const Scalar& friction) {
71 self.friction() = friction;
72 }
73 static ContactPatch copy(const ContactPatch& self) {
74 return ContactPatch(self);
75 }
76};
77} // namespace python
78} // namespace multicontact_api
79
80#endif // ifndef __multicontact_api_python_scenario_contact_patch_hpp__
Definition ellipsoid.hpp:12
static void setFriction(ContactPatch &self, const Scalar &friction)
Definition contact-patch.hpp:70
static void expose(const std::string &class_name)
Definition contact-patch.hpp:55
static ContactPatch copy(const ContactPatch &self)
Definition contact-patch.hpp:73
ContactPatch::SE3 SE3
Definition contact-patch.hpp:23
ContactPatch::Scalar Scalar
Definition contact-patch.hpp:22
static SE3 & getPlacement(ContactPatch &self)
Definition contact-patch.hpp:65
ContactPatch::ContactModel ContactModel
Definition contact-patch.hpp:24
static Scalar getFriction(ContactPatch &self)
Definition contact-patch.hpp:69
void visit(PyClass &cl) const
Definition contact-patch.hpp:27
static void setPlacement(ContactPatch &self, const SE3 &placement)
Definition contact-patch.hpp:66
Set the Python method str and repr to use the overloading operator<<.
Definition printable.hpp:19