Commit 3e7d4eff authored by Pierre Fernbach's avatar Pierre Fernbach
Browse files

[Scenario] add ContactPhase constructor with a contactModel

parent 3ff225a2
......@@ -19,6 +19,7 @@ template <typename ContactPatch>
struct ContactPatchPythonVisitor : public boost::python::def_visitor<ContactPatchPythonVisitor<ContactPatch> > {
typedef typename ContactPatch::Scalar Scalar;
typedef typename ContactPatch::SE3 SE3;
typedef typename ContactPatch::ContactModel ContactModel;
template <class PyClass>
void visit(PyClass& cl) const {
......@@ -26,6 +27,8 @@ struct ContactPatchPythonVisitor : public boost::python::def_visitor<ContactPatc
.def(bp::init<SE3>(bp::arg("placement"), "Init with a given placement."))
.def(bp::init<SE3, Scalar>(bp::args("placement", "friction"),
"Init with a given placement and friction coefficient."))
.def(bp::init<SE3, ContactModel>(bp::args("placement", "contact_model"),
"Init with a given placement and contact model."))
.def(bp::init<ContactPatch>(bp::arg("other"), "Copy contructor."))
.add_property("placement",
// getter require to use "make_function" to pass the return_internal_reference policy (return ref
......
......@@ -28,6 +28,9 @@ struct ContactPatchTpl : public serialization::Serializable<ContactPatchTpl<_Sca
/// \brief Init contact patch from a given placement and a friction coefficient
ContactPatchTpl(const SE3& placement, const Scalar mu) : m_contact_model(mu), m_placement(placement) {}
/// \brief Init contact patch from a given placement and a contact model
ContactPatchTpl(const SE3& placement, const ContactModel contact_model) : m_contact_model(contact_model), m_placement(placement) {}
/// \brief Copy constructor
ContactPatchTpl(const ContactPatchTpl& other)
: m_contact_model(other.m_contact_model), m_placement(other.m_placement) {}
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment