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