| Directory: | ./ |
|---|---|
| File: | bindings/python/crocoddyl/multibody/residuals/contact-force.cpp |
| Date: | 2025-03-26 19:23:43 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 20 | 21 | 95.2% |
| Branches: | 54 | 108 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh, | ||
| 5 | // Heriot-Watt University | ||
| 6 | // Copyright note valid unless otherwise stated in individual files. | ||
| 7 | // All rights reserved. | ||
| 8 | /////////////////////////////////////////////////////////////////////////////// | ||
| 9 | |||
| 10 | #include "crocoddyl/multibody/residuals/contact-force.hpp" | ||
| 11 | |||
| 12 | #include "python/crocoddyl/multibody/multibody.hpp" | ||
| 13 | #include "python/crocoddyl/utils/deprecate.hpp" | ||
| 14 | |||
| 15 | namespace crocoddyl { | ||
| 16 | namespace python { | ||
| 17 | |||
| 18 | template <typename Model> | ||
| 19 | struct ResidualModelContactForceVisitor | ||
| 20 | : public bp::def_visitor<ResidualModelContactForceVisitor<Model>> { | ||
| 21 | typedef typename Model::ResidualDataAbstract Data; | ||
| 22 | typedef typename Model::StateMultibody State; | ||
| 23 | typedef typename Model::Force Force; | ||
| 24 | typedef typename Model::VectorXs VectorXs; | ||
| 25 | template <class PyClass> | ||
| 26 | 40 | void visit(PyClass& cl) const { | |
| 27 |
2/4✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
40 | cl.def(bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Force, |
| 28 | std::size_t>( | ||
| 29 | bp::args("self", "state", "id", "fref", "nc"), | ||
| 30 | "Initialize the contact force residual model.\n\n" | ||
| 31 | "The default nu is obtained from state.nv. Note that this " | ||
| 32 | "constructor can be used for forward-dynamics cases only.\n" | ||
| 33 | ":param state: state of the multibody system\n" | ||
| 34 | ":param id: reference frame id\n" | ||
| 35 | ":param nc: dimension of the contact force (nc <= 6)\n" | ||
| 36 | ":param fref: reference spatial contact force in the contact " | ||
| 37 | "coordinates\n")) | ||
| 38 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
80 | .def( |
| 39 | "calc", | ||
| 40 | static_cast<void (Model::*)( | ||
| 41 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
| 42 | const Eigen::Ref<const VectorXs>&)>(&Model::calc), | ||
| 43 | bp::args("self", "data", "x", "u"), | ||
| 44 | "Compute the contact force residual.\n\n" | ||
| 45 | ":param data: residual data\n" | ||
| 46 | ":param x: state point (dim. state.nx)\n" | ||
| 47 | ":param u: control input (dim. nu)") | ||
| 48 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calc", |
| 49 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
| 50 | const Eigen::Ref<const VectorXs>&)>( | ||
| 51 | &Model::calc), | ||
| 52 | bp::args("self", "data", "x")) | ||
| 53 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def( |
| 54 | "calcDiff", | ||
| 55 | static_cast<void (Model::*)( | ||
| 56 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
| 57 | const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), | ||
| 58 | bp::args("self", "data", "x", "u"), | ||
| 59 | "Compute the Jacobians of the contact force residual.\n\n" | ||
| 60 | "It assumes that calc has been run first.\n" | ||
| 61 | ":param data: action data\n" | ||
| 62 | ":param x: state point (dim. state.nx)\n" | ||
| 63 | ":param u: control input (dim. nu)") | ||
| 64 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calcDiff", |
| 65 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
| 66 | const Eigen::Ref<const VectorXs>&)>( | ||
| 67 | &Model::calcDiff), | ||
| 68 | bp::args("self", "data", "x")) | ||
| 69 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("createData", &Model::createData, |
| 70 | ✗ | bp::with_custodian_and_ward_postcall<0, 2>(), | |
| 71 | bp::args("self", "data"), | ||
| 72 | "Create the contact force residual data.\n\n" | ||
| 73 | "Each residual model has its own data that needs to be allocated. " | ||
| 74 | "This function returns the allocated data for the contact force " | ||
| 75 | "residual.\n" | ||
| 76 | ":param data: shared data\n" | ||
| 77 | ":return residual data.") | ||
| 78 |
4/8✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
|
120 | .add_property( |
| 79 | "id", bp::make_function(&Model::get_id), | ||
| 80 | bp::make_function(&Model::set_id, | ||
| 81 |
2/4✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
80 | deprecated<>("Deprecated. Do not use set_id, " |
| 82 | "instead create a new model")), | ||
| 83 | "reference frame id") | ||
| 84 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property("reference", |
| 85 | bp::make_function( | ||
| 86 | &Model::get_reference, | ||
| 87 | 40 | bp::return_value_policy<bp::copy_const_reference>()), | |
| 88 | &Model::set_reference, "reference spatial force"); | ||
| 89 | 40 | } | |
| 90 | }; | ||
| 91 | |||
| 92 | template <typename Data> | ||
| 93 | struct ResidualDataContactForceVisitor | ||
| 94 | : public bp::def_visitor<ResidualDataContactForceVisitor<Data>> { | ||
| 95 | template <class PyClass> | ||
| 96 | 40 | void visit(PyClass& cl) const { | |
| 97 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
40 | cl.add_property( |
| 98 | "contact", | ||
| 99 | bp::make_getter(&Data::contact, | ||
| 100 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
| 101 | bp::make_setter(&Data::contact), | ||
| 102 | "contact data associated with the current residual"); | ||
| 103 | 40 | } | |
| 104 | }; | ||
| 105 | |||
| 106 | #define CROCODDYL_RESIDUAL_MODEL_CONTACT_FORCE_PYTHON_BINDINGS(Scalar) \ | ||
| 107 | typedef ResidualModelContactForceTpl<Scalar> Model; \ | ||
| 108 | typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ | ||
| 109 | typedef typename Model::StateMultibody State; \ | ||
| 110 | typedef typename Model::Force Force; \ | ||
| 111 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
| 112 | bp::class_<Model, bp::bases<ModelBase>>( \ | ||
| 113 | "ResidualModelContactForce", \ | ||
| 114 | "This residual function is defined as r = f-fref, where f,fref " \ | ||
| 115 | "describe the current and reference the spatial forces, respectively.", \ | ||
| 116 | bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Force, \ | ||
| 117 | std::size_t, std::size_t, bp::optional<bool>>( \ | ||
| 118 | bp::args("self", "state", "id", "fref", "nc", "nu", "fwddyn"), \ | ||
| 119 | "Initialize the contact force residual model.\n\n" \ | ||
| 120 | ":param state: state of the multibody system\n" \ | ||
| 121 | ":param id: reference frame id\n" \ | ||
| 122 | ":param fref: reference spatial contact force in the contact " \ | ||
| 123 | "coordinates\n" \ | ||
| 124 | ":param nc: dimension of the contact force (nc <= 6)\n" \ | ||
| 125 | ":param nu: dimension of control vector\n" \ | ||
| 126 | ":param fwddyn: indicate if we have a forward dynamics problem " \ | ||
| 127 | "(True) or inverse dynamics problem (False) (default True)")) \ | ||
| 128 | .def(ResidualModelContactForceVisitor<Model>()) \ | ||
| 129 | .def(CastVisitor<Model>()) \ | ||
| 130 | .def(PrintableVisitor<Model>()) \ | ||
| 131 | .def(CopyableVisitor<Model>()); | ||
| 132 | |||
| 133 | #define CROCODDYL_RESIDUAL_DATA_CONTACT_FORCE_PYTHON_BINDINGS(Scalar) \ | ||
| 134 | typedef ResidualDataContactForceTpl<Scalar> Data; \ | ||
| 135 | typedef ResidualDataAbstractTpl<Scalar> DataBase; \ | ||
| 136 | typedef ResidualModelContactForceTpl<Scalar> Model; \ | ||
| 137 | typedef Model::DataCollectorAbstract DataCollector; \ | ||
| 138 | bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ | ||
| 139 | bp::class_<Data, bp::bases<DataBase>>( \ | ||
| 140 | "ResidualDataContactForce", "Data for contact force residual.\n\n", \ | ||
| 141 | bp::init<Model*, DataCollector*>( \ | ||
| 142 | bp::args("self", "model", "data"), \ | ||
| 143 | "Create contact force residual data.\n\n" \ | ||
| 144 | ":param model: contact force residual model\n" \ | ||
| 145 | ":param data: shared data")[bp::with_custodian_and_ward< \ | ||
| 146 | 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ | ||
| 147 | .def(ResidualDataContactForceVisitor<Data>()) \ | ||
| 148 | .def(CopyableVisitor<Data>()); | ||
| 149 | |||
| 150 | 10 | void exposeResidualContactForce() { | |
| 151 |
17/34✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 10 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 10 times.
✗ Branch 19 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 10 times.
✗ Branch 31 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 10 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 10 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 10 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 10 times.
✗ Branch 54 not taken.
✓ Branch 56 taken 10 times.
✗ Branch 57 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS( |
| 152 | CROCODDYL_RESIDUAL_MODEL_CONTACT_FORCE_PYTHON_BINDINGS) | ||
| 153 |
15/30✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 10 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 not taken.
✓ Branch 21 taken 10 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 not taken.
✓ Branch 32 taken 10 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 10 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 10 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 10 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS( |
| 154 | CROCODDYL_RESIDUAL_DATA_CONTACT_FORCE_PYTHON_BINDINGS) | ||
| 155 | 10 | } | |
| 156 | |||
| 157 | } // namespace python | ||
| 158 | } // namespace crocoddyl | ||
| 159 |