| Directory: | ./ |
|---|---|
| File: | bindings/python/crocoddyl/core/residuals/joint-effort.cpp |
| Date: | 2025-03-26 19:23:43 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 16 | 17 | 94.1% |
| Branches: | 37 | 74 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2022-2025, Heriot-Watt University, University of Edinburgh | ||
| 5 | // Copyright note valid unless otherwise stated in individual files. | ||
| 6 | // All rights reserved. | ||
| 7 | /////////////////////////////////////////////////////////////////////////////// | ||
| 8 | |||
| 9 | #include "crocoddyl/core/residuals/joint-effort.hpp" | ||
| 10 | |||
| 11 | #include "python/crocoddyl/core/core.hpp" | ||
| 12 | |||
| 13 | namespace crocoddyl { | ||
| 14 | namespace python { | ||
| 15 | |||
| 16 | template <typename Model> | ||
| 17 | struct ResidualModelJointEffortVisitor | ||
| 18 | : public bp::def_visitor<ResidualModelJointEffortVisitor<Model>> { | ||
| 19 | typedef typename Model::ResidualDataAbstract Data; | ||
| 20 | typedef typename Model::Base ModelBase; | ||
| 21 | typedef typename Model::StateAbstract State; | ||
| 22 | typedef typename Model::ActuationModelAbstract Actuation; | ||
| 23 | typedef typename Model::VectorXs VectorXs; | ||
| 24 | template <class PyClass> | ||
| 25 | 40 | void visit(PyClass& cl) const { | |
| 26 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | cl.def( |
| 27 |
1/2✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
|
40 | bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>, |
| 28 | VectorXs>(bp::args("self", "state", "actuation", "uref"), | ||
| 29 | "Initialize the joint-effort residual model.\n\n" | ||
| 30 | "The default nu value is obtained from state.nv.\n" | ||
| 31 | ":param state: state description\n" | ||
| 32 | ":param actuation: actuation model\n" | ||
| 33 | ":param uref: reference joint effort")) | ||
| 34 |
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.
|
80 | .def(bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>, |
| 35 | std::size_t>( | ||
| 36 | bp::args("self", "state", "actuation", "nu"), | ||
| 37 | "Initialize the joint-effort residual model.\n\n" | ||
| 38 | "The default reference joint-effort is obtained from " | ||
| 39 | "np.zero(actuation.nu).\n" | ||
| 40 | ":param state: state description\n" | ||
| 41 | ":param actuation: actuation model\n" | ||
| 42 | ":param nu: dimension of the control vector")) | ||
| 43 |
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.
|
80 | .def(bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>>( |
| 44 | bp::args("self", "state", "actuation"), | ||
| 45 | "Initialize the joint-effort residual model.\n\n" | ||
| 46 | "The default reference joint-effort is obtained from " | ||
| 47 | "np.zero(actuation.nu).\n" | ||
| 48 | "The default nu value is obtained from state.nv.\n" | ||
| 49 | ":param state: state description\n" | ||
| 50 | ":param actuation: actuation model")) | ||
| 51 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
80 | .def( |
| 52 | "calc", | ||
| 53 | static_cast<void (Model::*)( | ||
| 54 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
| 55 | const Eigen::Ref<const VectorXs>&)>(&Model::calc), | ||
| 56 | bp::args("self", "data", "x", "u"), | ||
| 57 | "Compute the joint-effort residual.\n\n" | ||
| 58 | ":param data: residual data\n" | ||
| 59 | ":param x: state point (dim. state.nx)\n" | ||
| 60 | ":param u: control input (dim. nu)") | ||
| 61 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calc", |
| 62 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
| 63 | const Eigen::Ref<const VectorXs>&)>( | ||
| 64 | &Model::calc), | ||
| 65 | bp::args("self", "data", "x")) | ||
| 66 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def( |
| 67 | "calcDiff", | ||
| 68 | static_cast<void (Model::*)( | ||
| 69 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
| 70 | const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), | ||
| 71 | bp::args("self", "data", "x", "u"), | ||
| 72 | "Compute the Jacobians of the joint-effort residual.\n\n" | ||
| 73 | "It assumes that calc has been run first.\n" | ||
| 74 | ":param data: residual data\n" | ||
| 75 | ":param x: state point (dim. state.nx)\n" | ||
| 76 | ":param u: control input (dim. nu)") | ||
| 77 |
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.
|
80 | .def( |
| 78 | "calcDiff", | ||
| 79 | static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&, | ||
| 80 | const Eigen::Ref<const VectorXs>&)>( | ||
| 81 | &ModelBase::calcDiff), | ||
| 82 | bp::args("self", "data", "x")) | ||
| 83 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
80 | .def("createData", &Model::createData, |
| 84 | ✗ | bp::with_custodian_and_ward_postcall<0, 2>(), | |
| 85 | bp::args("self", "data"), | ||
| 86 | "Create the joint-effort residual data.\n\n" | ||
| 87 | "Each residual model has its own data that needs to be allocated. " | ||
| 88 | "This function\n" | ||
| 89 | "returns the allocated data for the joint-effort residual.\n" | ||
| 90 | ":param data: shared data\n" | ||
| 91 | ":return residual data.") | ||
| 92 |
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 | .add_property("reference", |
| 93 | bp::make_function(&Model::get_reference, | ||
| 94 | 40 | bp::return_internal_reference<>()), | |
| 95 | &Model::set_reference, "reference joint effort"); | ||
| 96 | 40 | } | |
| 97 | }; | ||
| 98 | |||
| 99 | #define CROCODDYL_RESIDUAL_MODEL_JOINTEFF_PYTHON_BINDINGS(Scalar) \ | ||
| 100 | typedef ResidualModelJointEffortTpl<Scalar> Model; \ | ||
| 101 | typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ | ||
| 102 | typedef typename ModelBase::StateAbstract State; \ | ||
| 103 | typedef typename Model::ActuationModelAbstract Actuation; \ | ||
| 104 | typedef typename ModelBase::VectorXs VectorXs; \ | ||
| 105 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
| 106 | bp::class_<Model, bp::bases<ModelBase>>( \ | ||
| 107 | "ResidualModelJointEffort", \ | ||
| 108 | "This residual function defines a residual vector as r = u - uref, " \ | ||
| 109 | "with u and uref as the current and reference joint efforts, " \ | ||
| 110 | "respectively.", \ | ||
| 111 | bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>, VectorXs, \ | ||
| 112 | std::size_t, bp::optional<bool>>( \ | ||
| 113 | bp::args("self", "state", "actuation", "uref", "nu", "fwddyn"), \ | ||
| 114 | "Initialize the joint-effort residual model.\n\n" \ | ||
| 115 | ":param state: state description\n" \ | ||
| 116 | ":param actuation: actuation model\n" \ | ||
| 117 | ":param uref: reference joint effort\n" \ | ||
| 118 | ":param nu: dimension of the control vector\n" \ | ||
| 119 | ":param fwddyn: indicate if we have a forward dynamics problem " \ | ||
| 120 | "(True) or inverse dynamics problem (False) (default False)")) \ | ||
| 121 | .def(ResidualModelJointEffortVisitor<Model>()) \ | ||
| 122 | .def(CastVisitor<Model>()) \ | ||
| 123 | .def(PrintableVisitor<Model>()) \ | ||
| 124 | .def(CopyableVisitor<Model>()); | ||
| 125 | |||
| 126 | 10 | void exposeResidualJointEffort() { | |
| 127 |
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(CROCODDYL_RESIDUAL_MODEL_JOINTEFF_PYTHON_BINDINGS) |
| 128 | 10 | } | |
| 129 | |||
| 130 | } // namespace python | ||
| 131 | } // namespace crocoddyl | ||
| 132 |