| Directory: | ./ |
|---|---|
| File: | include/multicontact-api/bindings/python/scenario/contact-phase.hpp |
| Date: | 2025-04-05 01:06:26 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 171 | 171 | 100.0% |
| Branches: | 149 | 294 | 50.7% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // Copyright (c) 2015-2018, CNRS | ||
| 2 | // Authors: Justin Carpentier <jcarpent@laas.fr> | ||
| 3 | |||
| 4 | #ifndef __multicontact_api_python_scenario_contact_phase_hpp__ | ||
| 5 | #define __multicontact_api_python_scenario_contact_phase_hpp__ | ||
| 6 | |||
| 7 | #include <pinocchio/fwd.hpp> | ||
| 8 | // Include pinocchio before everything else | ||
| 9 | #include <ndcurves/python/python_definitions.h> | ||
| 10 | |||
| 11 | #include <boost/python/suite/indexing/map_indexing_suite.hpp> | ||
| 12 | #include <boost/python/suite/indexing/vector_indexing_suite.hpp> | ||
| 13 | #include <eigenpy/eigenpy.hpp> | ||
| 14 | #include <typeinfo> | ||
| 15 | |||
| 16 | #include "multicontact-api/bindings/python/serialization/archive.hpp" | ||
| 17 | #include "multicontact-api/bindings/python/utils/printable.hpp" | ||
| 18 | #include "multicontact-api/scenario/contact-phase.hpp" | ||
| 19 | |||
| 20 | namespace multicontact_api { | ||
| 21 | namespace python { | ||
| 22 | |||
| 23 | namespace bp = boost::python; | ||
| 24 | |||
| 25 | template <typename ContactPhase> | ||
| 26 | struct ContactPhasePythonVisitor | ||
| 27 | : public bp::def_visitor<ContactPhasePythonVisitor<ContactPhase> > { | ||
| 28 | typedef typename ContactPhase::Scalar Scalar; | ||
| 29 | typedef typename ContactPhase::ContactPatch ContactPatch; | ||
| 30 | typedef typename ContactPhase::SE3 SE3; | ||
| 31 | typedef typename ContactPhase::t_strings t_strings; | ||
| 32 | typedef typename ContactPhase::curve_ptr curve_ptr; | ||
| 33 | typedef typename ContactPhase::curve_SE3_ptr curve_SE3_ptr; | ||
| 34 | typedef typename ContactPhase::point3_t point3_t; | ||
| 35 | typedef typename ContactPhase::point6_t point6_t; | ||
| 36 | typedef typename ContactPhase::pointX_t pointX_t; | ||
| 37 | typedef ndcurves::t_pointX_t t_pointX_t; | ||
| 38 | typedef ndcurves::t_time_t t_time_t; | ||
| 39 | typedef ndcurves::pointX_list_t pointX_list_t; | ||
| 40 | typedef ndcurves::time_waypoints_t time_waypoints_t; | ||
| 41 | |||
| 42 | // call macro for all ContactPhase methods that can be overloaded | ||
| 43 | 6 | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(isConsistent_overloads, | |
| 44 | ContactPhase::isConsistent, 0, 1) | ||
| 45 | |||
| 46 | template <class PyClass> | ||
| 47 | 3 | void visit(PyClass& cl) const { | |
| 48 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
|
3 | cl.def(bp::init<>(bp::arg(""), "Default constructor.")) |
| 49 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .def(bp::init<Scalar, Scalar>(bp::args("t_init", "t_final"), |
| 50 | "Constructor with time interval.")) | ||
| 51 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .def(bp::init<ContactPhase>(bp::arg("other"), "Copy contructor.")) |
| 52 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .add_property("timeInitial", &getTimeInitial, &setTimeInitial, |
| 53 | "The time at the begining of this contact phase.") | ||
| 54 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .add_property("timeFinal", &getTimeFinal, &setTimeFinal, |
| 55 | "The time at the end of this contact phase.") | ||
| 56 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .add_property("duration", &getDuration, &setDuration, |
| 57 | "The duration this contact phase.") | ||
| 58 | // expose public members : | ||
| 59 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 60 | "c_init", | ||
| 61 | bp::make_getter(&ContactPhase::m_c_init, | ||
| 62 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 63 | bp::make_setter(&ContactPhase::m_c_init), | ||
| 64 | "Initial 3D position of the center of mass for this contact phase") | ||
| 65 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 66 | "dc_init", | ||
| 67 | bp::make_getter(&ContactPhase::m_dc_init, | ||
| 68 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 69 | bp::make_setter(&ContactPhase::m_dc_init), | ||
| 70 | "Initial linear velocity of the center of mass for this contact " | ||
| 71 | "phase") | ||
| 72 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 73 | "ddc_init", | ||
| 74 | bp::make_getter(&ContactPhase::m_ddc_init, | ||
| 75 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 76 | bp::make_setter(&ContactPhase::m_ddc_init), | ||
| 77 | "Initial linear acceleration of the center of mass for this " | ||
| 78 | "contact phase") | ||
| 79 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 80 | "L_init", | ||
| 81 | bp::make_getter(&ContactPhase::m_L_init, | ||
| 82 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 83 | bp::make_setter(&ContactPhase::m_L_init), | ||
| 84 | "Initial angular momentum for this contact phase") | ||
| 85 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 86 | "dL_init", | ||
| 87 | bp::make_getter(&ContactPhase::m_dL_init, | ||
| 88 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 89 | bp::make_setter(&ContactPhase::m_dL_init), | ||
| 90 | "Initial angular momentum derivative for this contact phase") | ||
| 91 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 92 | "q_init", | ||
| 93 | bp::make_getter(&ContactPhase::m_q_init, | ||
| 94 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 95 | bp::make_setter(&ContactPhase::m_q_init), | ||
| 96 | "Initial whole body configuration of this phase") | ||
| 97 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 98 | "c_final", | ||
| 99 | bp::make_getter(&ContactPhase::m_c_final, | ||
| 100 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 101 | bp::make_setter(&ContactPhase::m_c_final), | ||
| 102 | "Final 3D position of the center of mass for this contact phase") | ||
| 103 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 104 | "dc_final", | ||
| 105 | bp::make_getter(&ContactPhase::m_dc_final, | ||
| 106 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 107 | bp::make_setter(&ContactPhase::m_dc_final), | ||
| 108 | "Final linear velocity of the center of mass for this contact " | ||
| 109 | "phase") | ||
| 110 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 111 | "ddc_final", | ||
| 112 | bp::make_getter(&ContactPhase::m_ddc_final, | ||
| 113 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 114 | bp::make_setter(&ContactPhase::m_ddc_final), | ||
| 115 | "Final linear acceleration of the center of mass for this contact " | ||
| 116 | "phase") | ||
| 117 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 118 | "L_final", | ||
| 119 | bp::make_getter(&ContactPhase::m_L_final, | ||
| 120 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 121 | bp::make_setter(&ContactPhase::m_L_final), | ||
| 122 | "Final angular momentum for this contact phase") | ||
| 123 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 124 | "dL_final", | ||
| 125 | bp::make_getter(&ContactPhase::m_dL_final, | ||
| 126 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 127 | bp::make_setter(&ContactPhase::m_dL_final), | ||
| 128 | "Final angular momentum derivative for this contact phase") | ||
| 129 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .add_property( |
| 130 | "q_final", | ||
| 131 | bp::make_getter(&ContactPhase::m_q_final, | ||
| 132 | 3 | bp::return_value_policy<bp::return_by_value>()), | |
| 133 | bp::make_setter(&ContactPhase::m_q_final), | ||
| 134 | "Final whole body configuration of this phase") | ||
| 135 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("q_t", &ContactPhase::m_q) |
| 136 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("dq_t", &ContactPhase::m_dq) |
| 137 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("ddq_t", &ContactPhase::m_ddq) |
| 138 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("tau_t", &ContactPhase::m_tau) |
| 139 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("c_t", &ContactPhase::m_c) |
| 140 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("dc_t", &ContactPhase::m_dc) |
| 141 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("ddc_t", &ContactPhase::m_ddc) |
| 142 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("L_t", &ContactPhase::m_L) |
| 143 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("dL_t", &ContactPhase::m_dL) |
| 144 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("wrench_t", &ContactPhase::m_wrench) |
| 145 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("zmp_t", &ContactPhase::m_zmp) |
| 146 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def_readwrite("root_t", &ContactPhase::m_root) |
| 147 | // accessor to map with key | ||
| 148 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("contactForce", &contactForcesFromKey, bp::arg("effector_name"), |
| 149 | "Return a pointer to the contact force trajectory for this " | ||
| 150 | "effector.\n" | ||
| 151 | "Throw a ValueError if the effector is not in contact.") | ||
| 152 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("contactNormalForce", &contactNormalForcesFromKey, |
| 153 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("effector_name"), |
| 154 | "Return a pointer to the contact normal force trajectory for this " | ||
| 155 | "effector.\n" | ||
| 156 | "Throw a ValueError if the effector is not in contact.") | ||
| 157 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("effectorTrajectory", &effectorTrajectoriesFromKey, |
| 158 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("effector_name"), |
| 159 | "Return a pointer to the effector trajectory (in SE3) for this " | ||
| 160 | "effector.\n" | ||
| 161 | "Throw a ValueError if the effector is in contact.") | ||
| 162 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
3 | .def("contactPatch", &contactPatchFromKey, bp::arg("effector_name"), |
| 163 | 3 | bp::return_internal_reference<>(), | |
| 164 | "Return the ContactPatch object for this effector.\n" | ||
| 165 | "Throw a ValueError if the effector is not in contact.") | ||
| 166 | // Bindings of the maps: | ||
| 167 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("contactPatches", &contactPatchesAsDict, |
| 168 | "Return a CONST dict EffectorName:ContactPatch") | ||
| 169 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("contactForces", &contactForcesAsDict, |
| 170 | "Return a CONST dict EffectorName:contact force") | ||
| 171 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("contactNormalForces", &contactNormalForcesAsDict, |
| 172 | "Return a CONST dict EffectorName:contact normal force") | ||
| 173 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("effectorTrajectories", &effectorTrajectoriesAsDict, |
| 174 | "Return a CONST dict EffectorName:effector trajectory") | ||
| 175 | // adding trajectory to map : | ||
| 176 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | .def("addContactForceTrajectory", |
| 177 | &ContactPhase::addContactForceTrajectory, | ||
| 178 | bp::args("effector_name", "trajectory"), | ||
| 179 | "Add a trajectory to the map of contact forces.\n" | ||
| 180 | "If a trajectory already exist for this effector, it is " | ||
| 181 | "overwritted.\n" | ||
| 182 | "Throw invalid_argument if eeName is not defined in contact for " | ||
| 183 | "this phase.\n" | ||
| 184 | "Return false if a trajectory already existed (and have been " | ||
| 185 | "overwrited) true otherwise.") | ||
| 186 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("addContactNormalForceTrajectory", |
| 187 | &ContactPhase::addContactNormalForceTrajectory, | ||
| 188 | bp::args("effector_name", "trajectory"), | ||
| 189 | "Add a trajectory to the map of contact normal forces.\n" | ||
| 190 | "If a trajectory already exist for this effector, it is " | ||
| 191 | "overwritted.\n" | ||
| 192 | "Throw a ValueError if eeName is not defined in contact for this " | ||
| 193 | "phase.\n" | ||
| 194 | "Throw a ValueError if trajectory is not of dimension 1.\n" | ||
| 195 | "Return false if a trajectory already existed (and have been " | ||
| 196 | "overwrited) true otherwise.") | ||
| 197 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("addEffectorTrajectory", &ContactPhase::addEffectorTrajectory, |
| 198 | bp::args("effector_name", "trajectory"), | ||
| 199 | "Add a trajectory to the map of effector trajectories.\n" | ||
| 200 | "If a trajectory already exist for this effector, it is " | ||
| 201 | "overwritted.\n" | ||
| 202 | "Throw a ValueError if eeName is defined in contact for this " | ||
| 203 | "phase.\n" | ||
| 204 | "Return false if a trajectory already existed (and have been " | ||
| 205 | "overwrited) true otherwise.") | ||
| 206 | // contacts | ||
| 207 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("addContact", &ContactPhase::addContact, |
| 208 | bp::args("effector_name", "patch"), | ||
| 209 | "Add a new contact patch for effector_name to this contact phase\n" | ||
| 210 | "If a contact phase already exist for this effector, it is " | ||
| 211 | "overwritted.\n" | ||
| 212 | "If an end effector trajectory exist for this contact, it is " | ||
| 213 | "removed.\n" | ||
| 214 | "Return false if a contact for this effector already existed (and " | ||
| 215 | "have been overwrited) true otherwise.") | ||
| 216 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("removeContact", &ContactPhase::removeContact, |
| 217 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("effector_name"), |
| 218 | "Remove the contact for effector_name.\n" | ||
| 219 | "This will also remove the contact_patch, all the contact_forces " | ||
| 220 | "and contact_normal_forces related to " | ||
| 221 | "this contact.\n" | ||
| 222 | "Return true if the effector was in contact, false otherwise") | ||
| 223 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("numContacts", &ContactPhase::numContacts, |
| 224 | "Returns the number of active contacts.") | ||
| 225 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("isEffectorInContact", &ContactPhase::isEffectorInContact, |
| 226 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("effector_name"), |
| 227 | "Returns True if the given effector_name is in contact for this " | ||
| 228 | "phase, False otherwise.") | ||
| 229 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
3 | .def("effectorsInContact", &effectorsInContactAsList, |
| 230 | "Returns the names of the effectors in contact.") | ||
| 231 | 6 | .def("effectorHaveAtrajectory", &ContactPhase::effectorHaveAtrajectory, | |
| 232 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("effector_name"), |
| 233 | "Returns True if the given effector_name have an " | ||
| 234 | "effector_trajectory defined in this phase, False " | ||
| 235 | "otherwise.") | ||
| 236 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
3 | .def("effectorsWithTrajectory", &effectorsWithTrajectoryAsList, |
| 237 | "Returns the names of the effectors for which an end effector " | ||
| 238 | "trajectory have been defined in this phase.") | ||
| 239 | 6 | .def("isConsistent", &ContactPhase::isConsistent, | |
| 240 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | isConsistent_overloads(bp::arg("throw_if_invalid"), |
| 241 | "isConsistent check if all the members of " | ||
| 242 | "the phase are consistent together.\n" | ||
| 243 | "if throw_if_invalid == True it raise an " | ||
| 244 | "error instead of returning False.")) | ||
| 245 |
3/6✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
|
6 | .def("getContactsBroken", &getContactsBrokenAsList, bp::arg("to"), |
| 246 | "return the list of effectors in contact in '*this' but not in " | ||
| 247 | "contact in 'to'") | ||
| 248 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("getContactsCreated", &getContactsCreatedAsList, bp::arg("to"), |
| 249 | "getContactsCreated return the list of effectors in contact in " | ||
| 250 | "'to' but not in contact in '*this'") | ||
| 251 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("getContactsRepositioned", &getContactsRepositionedAsList, |
| 252 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("to"), |
| 253 | "return the list of effectors in contact both in 'to' and '*this' " | ||
| 254 | "but not at the same placement") | ||
| 255 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("getContactsVariations", &getContactsVariationsAsList, |
| 256 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
6 | bp::arg("to"), |
| 257 | "return the list of all the effectors whose contacts differ " | ||
| 258 | "between *this and to") | ||
| 259 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("setCOMtrajectoryFromPoints", &setCOMtrajectoryFromPoints, |
| 260 | bp::args("COM_positions", "COM_velocities", "COM_accelerations", | ||
| 261 | "times"), | ||
| 262 | "set the c,dc and ddc curves from a list of discrete" | ||
| 263 | "COM positions, velocity and accelerations.\n" | ||
| 264 | "The trajectories are build with first order polynomials " | ||
| 265 | "connecting each discrete points given.\n" | ||
| 266 | "This method also set the initial/final values for c, dc and ddc " | ||
| 267 | "from the first and last discrete point " | ||
| 268 | "given.") | ||
| 269 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("setAMtrajectoryFromPoints", &setAMtrajectoryFromPoints, |
| 270 | bp::args("AM_values", "AM_derivatives", "times"), | ||
| 271 | "set the L and d_L curves from a list of discrete Angular " | ||
| 272 | "velocity values and their derivatives.\n" | ||
| 273 | "The trajectories are build with first order polynomials " | ||
| 274 | "connecting each discrete points given.\n" | ||
| 275 | "This method also set the initial/final values for L, and dL from " | ||
| 276 | "the first and last discrete point " | ||
| 277 | "given.") | ||
| 278 |
2/4✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
6 | .def("setJointsTrajectoryFromPoints", &setJointsTrajectoryFromPoints, |
| 279 | bp::args("Joints_poisitions", "Joints_velocities", | ||
| 280 | "Joints_accelerations", "times"), | ||
| 281 | "set the q,dq and ddq curves from a list of discrete joints " | ||
| 282 | "positions, velocity and accelerations." | ||
| 283 | "The trajectories are build with first order polynomials " | ||
| 284 | "connecting each discrete points given.\n" | ||
| 285 | "This method also set initial/final values for q from the first " | ||
| 286 | "and last discrete point given.\n") | ||
| 287 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | .def(bp::self == bp::self) |
| 288 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
6 | .def(bp::self != bp::self) |
| 289 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def("copy", ©, "Returns a copy of *this."); |
| 290 | 3 | } | |
| 291 | |||
| 292 | 3 | static void expose(const std::string& class_name) { | |
| 293 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | std::string doc = "Contact Phase"; |
| 294 |
1/2✓ Branch 3 taken 3 times.
✗ Branch 4 not taken.
|
3 | bp::class_<ContactPhase>(class_name.c_str(), doc.c_str(), bp::no_init) |
| 295 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def(ContactPhasePythonVisitor<ContactPhase>()) |
| 296 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def(SerializableVisitor<ContactPhase>()) |
| 297 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | .def(PrintableVisitor<ContactPhase>()); |
| 298 | |||
| 299 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | ENABLE_SPECIFIC_MATRIX_TYPE(point3_t); |
| 300 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | ENABLE_SPECIFIC_MATRIX_TYPE(point6_t); |
| 301 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | ENABLE_SPECIFIC_MATRIX_TYPE(pointX_t); |
| 302 | 3 | } | |
| 303 | |||
| 304 | protected: | ||
| 305 | // define getter and setter (because they are overloaded in c++) | ||
| 306 | 9 | static Scalar getTimeInitial(ContactPhase& self) { | |
| 307 | 9 | return self.timeInitial(); | |
| 308 | } | ||
| 309 | 3 | static void setTimeInitial(ContactPhase& self, const Scalar& time) { | |
| 310 | 3 | self.timeInitial(time); | |
| 311 | 3 | } | |
| 312 | 14 | static Scalar getTimeFinal(ContactPhase& self) { return self.timeFinal(); } | |
| 313 | 4 | static void setTimeFinal(ContactPhase& self, const Scalar& time) { | |
| 314 | 4 | self.timeFinal(time); | |
| 315 | 3 | } | |
| 316 | 8 | static Scalar getDuration(ContactPhase& self) { return self.duration(); } | |
| 317 | 9 | static void setDuration(ContactPhase& self, const Scalar& time) { | |
| 318 | 9 | self.duration(time); | |
| 319 | 8 | } | |
| 320 | |||
| 321 | // accessor to map with key: | ||
| 322 | 15 | static curve_ptr contactForcesFromKey(ContactPhase& self, | |
| 323 | const std::string& eeName) { | ||
| 324 | 15 | return self.contactForces(eeName); | |
| 325 | } | ||
| 326 | 15 | static curve_ptr contactNormalForcesFromKey(ContactPhase& self, | |
| 327 | const std::string& eeName) { | ||
| 328 | 15 | return self.contactNormalForces(eeName); | |
| 329 | } | ||
| 330 | 17 | static curve_SE3_ptr effectorTrajectoriesFromKey(ContactPhase& self, | |
| 331 | const std::string& eeName) { | ||
| 332 | 17 | return self.effectorTrajectories(eeName); | |
| 333 | } | ||
| 334 | 49 | static ContactPatch& contactPatchFromKey(ContactPhase& self, | |
| 335 | const std::string& eeName) { | ||
| 336 | 49 | return self.contactPatch(eeName); | |
| 337 | } | ||
| 338 | |||
| 339 | // Converts a C++ vector to a python list | ||
| 340 | // Note : lot of overhead, should not be used for large vector and/or | ||
| 341 | // operations called frequently. prefer the direct bindings with | ||
| 342 | // std_vector_strings for this cases. | ||
| 343 | template <class T> | ||
| 344 | 21 | static bp::list toPythonList(std::vector<T> vector) { | |
| 345 | 21 | typename std::vector<T>::const_iterator iter; | |
| 346 |
1/2✓ Branch 1 taken 21 times.
✗ Branch 2 not taken.
|
21 | boost::python::list list; |
| 347 |
2/2✓ Branch 5 taken 22 times.
✓ Branch 6 taken 21 times.
|
43 | for (iter = vector.begin(); iter != vector.end(); ++iter) { |
| 348 |
1/2✓ Branch 2 taken 22 times.
✗ Branch 3 not taken.
|
22 | list.append(*iter); |
| 349 | } | ||
| 350 | 42 | return list; | |
| 351 | } | ||
| 352 | 9 | static bp::list effectorsInContactAsList(ContactPhase& self) { | |
| 353 |
1/2✓ Branch 2 taken 9 times.
✗ Branch 3 not taken.
|
9 | return toPythonList<std::string>(self.effectorsInContact()); |
| 354 | } | ||
| 355 | 3 | static bp::list effectorsWithTrajectoryAsList(ContactPhase& self) { | |
| 356 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | return toPythonList<std::string>(self.effectorsWithTrajectory()); |
| 357 | } | ||
| 358 | 2 | static bp::list getContactsBrokenAsList(ContactPhase& self, | |
| 359 | const ContactPhase& to) { | ||
| 360 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
2 | return toPythonList<std::string>(self.getContactsBroken(to)); |
| 361 | } | ||
| 362 | 2 | static bp::list getContactsCreatedAsList(ContactPhase& self, | |
| 363 | const ContactPhase& to) { | ||
| 364 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
2 | return toPythonList<std::string>(self.getContactsCreated(to)); |
| 365 | } | ||
| 366 | 2 | static bp::list getContactsRepositionedAsList(ContactPhase& self, | |
| 367 | const ContactPhase& to) { | ||
| 368 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
2 | return toPythonList<std::string>(self.getContactsRepositioned(to)); |
| 369 | } | ||
| 370 | 3 | static bp::list getContactsVariationsAsList(ContactPhase& self, | |
| 371 | const ContactPhase& to) { | ||
| 372 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | return toPythonList<std::string>(self.getContactsVariations(to)); |
| 373 | } | ||
| 374 | |||
| 375 | // Converts a C++ map to a python dict | ||
| 376 | // Note : lot of overhead, should not be used for large map and/or operations | ||
| 377 | // called frequently. prefer the direct bindings with std_map_* for this | ||
| 378 | // cases. | ||
| 379 | template <class T> | ||
| 380 | 40 | static bp::dict toPythonDict(std::map<std::string, T> map) { | |
| 381 | 40 | typename std::map<std::string, T>::const_iterator iter; | |
| 382 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | bp::dict dict; |
| 383 |
2/2✓ Branch 5 taken 32 times.
✓ Branch 6 taken 20 times.
|
104 | for (iter = map.begin(); iter != map.end(); ++iter) { |
| 384 |
2/4✓ Branch 3 taken 32 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 32 times.
✗ Branch 7 not taken.
|
64 | dict[iter->first] = iter->second; |
| 385 | } | ||
| 386 | 80 | return dict; | |
| 387 | } | ||
| 388 | |||
| 389 | 6 | static bp::dict contactPatchesAsDict(ContactPhase& self) { | |
| 390 |
1/2✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
|
6 | return toPythonDict<ContactPatch>(self.contactPatches()); |
| 391 | } | ||
| 392 | 5 | static bp::dict contactForcesAsDict(ContactPhase& self) { | |
| 393 |
1/2✓ Branch 3 taken 5 times.
✗ Branch 4 not taken.
|
5 | return toPythonDict<curve_ptr>(self.contactForces()); |
| 394 | } | ||
| 395 | 5 | static bp::dict contactNormalForcesAsDict(ContactPhase& self) { | |
| 396 |
1/2✓ Branch 3 taken 5 times.
✗ Branch 4 not taken.
|
5 | return toPythonDict<curve_ptr>(self.contactNormalForces()); |
| 397 | } | ||
| 398 | 4 | static bp::dict effectorTrajectoriesAsDict(ContactPhase& self) { | |
| 399 |
1/2✓ Branch 3 taken 4 times.
✗ Branch 4 not taken.
|
4 | return toPythonDict<curve_SE3_ptr>(self.effectorTrajectories()); |
| 400 | } | ||
| 401 | |||
| 402 | 1 | static void setCOMtrajectoryFromPoints( | |
| 403 | ContactPhase& self, const pointX_list_t& points, | ||
| 404 | const pointX_list_t& points_derivative, | ||
| 405 | const pointX_list_t& points_second_derivative, | ||
| 406 | const time_waypoints_t& time_points) { | ||
| 407 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_list = |
| 408 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>(points); | ||
| 409 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_derivative_list = |
| 410 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>( | ||
| 411 | points_derivative); | ||
| 412 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_second_derivative_list = |
| 413 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>( | ||
| 414 | points_second_derivative); | ||
| 415 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_time_t time_points_list = |
| 416 | ndcurves::vectorFromEigenVector<time_waypoints_t, t_time_t>( | ||
| 417 | time_points); | ||
| 418 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | self.setCOMtrajectoryFromPoints(points_list, points_derivative_list, |
| 419 | points_second_derivative_list, | ||
| 420 | time_points_list); | ||
| 421 | 2 | return; | |
| 422 | 1 | } | |
| 423 | |||
| 424 | 1 | static void setJointsTrajectoryFromPoints( | |
| 425 | ContactPhase& self, const pointX_list_t& points, | ||
| 426 | const pointX_list_t& points_derivative, | ||
| 427 | const pointX_list_t& points_second_derivative, | ||
| 428 | const time_waypoints_t& time_points) { | ||
| 429 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_list = |
| 430 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>(points); | ||
| 431 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_derivative_list = |
| 432 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>( | ||
| 433 | points_derivative); | ||
| 434 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_second_derivative_list = |
| 435 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>( | ||
| 436 | points_second_derivative); | ||
| 437 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_time_t time_points_list = |
| 438 | ndcurves::vectorFromEigenVector<time_waypoints_t, t_time_t>( | ||
| 439 | time_points); | ||
| 440 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | self.setJointsTrajectoryFromPoints(points_list, points_derivative_list, |
| 441 | points_second_derivative_list, | ||
| 442 | time_points_list); | ||
| 443 | 2 | return; | |
| 444 | 1 | } | |
| 445 | |||
| 446 | 1 | static void setAMtrajectoryFromPoints(ContactPhase& self, | |
| 447 | const pointX_list_t& points, | ||
| 448 | const pointX_list_t& points_derivative, | ||
| 449 | const time_waypoints_t& time_points) { | ||
| 450 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_list = |
| 451 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>(points); | ||
| 452 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_pointX_t points_derivative_list = |
| 453 | ndcurves::vectorFromEigenArray<pointX_list_t, t_pointX_t>( | ||
| 454 | points_derivative); | ||
| 455 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | t_time_t time_points_list = |
| 456 | ndcurves::vectorFromEigenVector<time_waypoints_t, t_time_t>( | ||
| 457 | time_points); | ||
| 458 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | self.setAMtrajectoryFromPoints(points_list, points_derivative_list, |
| 459 | time_points_list); | ||
| 460 | 2 | return; | |
| 461 | 1 | } | |
| 462 | |||
| 463 | 1 | static ContactPhase copy(const ContactPhase& self) { | |
| 464 | 1 | return ContactPhase(self); | |
| 465 | } | ||
| 466 | }; | ||
| 467 | } // namespace python | ||
| 468 | } // namespace multicontact_api | ||
| 469 | |||
| 470 | #endif // ifndef __multicontact_api_python_scenario_contact_phase_hpp__ | ||
| 471 |