Skip to content

Commit

Permalink
Merge pull request #19 from pFernbach/devel
Browse files Browse the repository at this point in the history
Add jupyter notebooks
  • Loading branch information
nim65s authored Dec 9, 2021
2 parents 50bdf62 + ff7175c commit b4a2569
Show file tree
Hide file tree
Showing 8 changed files with 3,841 additions and 4 deletions.
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,13 @@ make test

## Main classes

This package define 3 main classes representing physical concepts of legged locomotion. Contact Patch, Contact Phase and Contact Sequence.
This package define 4 main classes representing physical concepts of legged locomotion. Contact Model, Contact Patch, Contact Phase and Contact Sequence.

### Contact Patch
A Contact Model define the physical properties of a contact. A Contact Patch define completely a contact between a part of the robot and the environment, it contain a Contact Model. A Contact Phase is defined by a constant set of contacts, it contains one or more Contact Patches. Finally, a Contact Sequence is a sequence of Contact Phases.

A contact patch define the placement (in SE(3), in the world frame) of a contact as long as the friction coefficient for this contact.
### Contact Patch

Future work will also include the type of contact (eg planar, punctual, bilateral ...), a representation of the friction cone or additional information about the contact.
A contact patch define the placement (in SE(3), in the world frame) of a contact between a part of the robot and the environment. It contains a ContactModel.

### Contact Phase

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,16 @@ 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 {
cl.def(bp::init<>(bp::arg(""), "Default constructor."))
.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
Expand Down
3 changes: 3 additions & 0 deletions include/multicontact-api/scenario/contact-patch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {}
Expand Down
Loading

0 comments on commit b4a2569

Please sign in to comment.