| Directory: | ./ | 
|---|---|
| File: | bindings/python/crocoddyl/core/state-base.cpp | 
| Date: | 2025-03-26 19:23:43 | 
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 36 | 36 | 100.0% | 
| Branches: | 60 | 120 | 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 "python/crocoddyl/core/state-base.hpp" | ||
| 11 | |||
| 12 | #include "python/crocoddyl/core/core.hpp" | ||
| 13 | |||
| 14 | namespace crocoddyl { | ||
| 15 | namespace python { | ||
| 16 | |||
| 17 | template <typename State> | ||
| 18 | struct StateAbstractVisitor | ||
| 19 | : public bp::def_visitor<StateAbstractVisitor<State>> { | ||
| 20 | typedef typename State::Scalar Scalar; | ||
| 21 | template <class PyClass> | ||
| 22 | 40 | void visit(PyClass& cl) const { | |
| 23 | 
        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::size_t, std::size_t>( | 
| 24 | bp::args("self", "nx", "ndx"), | ||
| 25 | "Initialize the state dimensions.\n\n" | ||
| 26 | ":param nx: dimension of state configuration tuple\n" | ||
| 27 | ":param ndx: dimension of state tangent vector")) | ||
| 28 | 
        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("zero", pure_virtual(&State::zero), bp::args("self"), | 
| 29 | "Generate a zero reference state.\n\n" | ||
| 30 | ":return zero reference state") | ||
| 31 | 
        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("rand", pure_virtual(&State::rand), bp::args("self"), | 
| 32 | "Generate a random reference state.\n\n" | ||
| 33 | ":return random reference state") | ||
| 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("diff", pure_virtual(&State::diff_wrap), | 
| 35 | bp::args("self", "x0", "x1"), | ||
| 36 | "Compute the state manifold differentiation.\n\n" | ||
| 37 | "It returns the value of x1 [-] x0 operation. Note tha x0 and x1 " | ||
| 38 | "are points in the state manifold (in M). Instead the operator " | ||
| 39 | "result lies in the tangent-space of M.\n" | ||
| 40 | ":param x0: previous state point (dim state.nx).\n" | ||
| 41 | ":param x1: current state point (dim state.nx).\n" | ||
| 42 | ":return x1 [-] x0 value (dim state.ndx).") | ||
| 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("integrate", pure_virtual(&State::integrate_wrap), | 
| 44 | bp::args("self", "x", "dx"), | ||
| 45 | "Compute the state manifold integration.\n\n" | ||
| 46 | "It returns the value of x [+] dx operation. x and dx are points " | ||
| 47 | "in the state.diff(x0,x1) (in M) and its tangent, respectively. " | ||
| 48 | "Note that the operator result lies on M too.\n" | ||
| 49 | ":param x: state point (dim. state.nx).\n" | ||
| 50 | ":param dx: velocity vector (dim state.ndx).\n" | ||
| 51 | ":return x [+] dx value (dim state.nx).") | ||
| 52 | 
        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("Jdiff", pure_virtual(&State::Jdiff_wrap), | 
| 53 | bp::args("self", "x0", "x1", "firstsecond"), | ||
| 54 | "Compute the partial derivatives of difference operator.\n\n" | ||
| 55 | "The difference operator (x1 [-] x0) is defined by diff(x0, x1). " | ||
| 56 | "Instead Jdiff computes its partial derivatives, i.e. " | ||
| 57 | "\\partial{diff(x0, x1)}{x0} and \\partial{diff(x0, x1)}{x1}. By " | ||
| 58 | "default, this function returns the derivatives of the first and " | ||
| 59 | "second argument (i.e. firstsecond='both'). However we can also " | ||
| 60 | "specific the partial derivative for the first and second " | ||
| 61 | "variables by setting firstsecond='first' or " | ||
| 62 | "firstsecond='second', respectively.\n" | ||
| 63 | ":param x0: previous state point (dim state.nx).\n" | ||
| 64 | ":param x1: current state point (dim state.nx).\n" | ||
| 65 | ":param firstsecond: derivative w.r.t x0 or x1 or both\n" | ||
| 66 | ":return the partial derivative(s) of the diff(x0, x1) function") | ||
| 67 | 
        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("Jintegrate", pure_virtual(&State::Jintegrate_wrap), | 
| 68 | bp::args("self", "x", "dx", "firstsecond"), | ||
| 69 | "Compute the partial derivatives of integrate operator.\n\n" | ||
| 70 | "The integrate operator (x [+] dx) is defined by integrate(x, " | ||
| 71 | "dx). Instead Jintegrate computes its partial derivatives, i.e. " | ||
| 72 | "\\partial{integrate(x, dx)}{x} and \\partial{integrate(x, " | ||
| 73 | "dx)}{dx}. By default, this function returns the derivatives of " | ||
| 74 | "the first and second argument (i.e. firstsecond='both'), partial " | ||
| 75 | "derivative by setting firstsecond='first' or " | ||
| 76 | "firstsecond='second'.\n" | ||
| 77 | ":param x: state point (dim. state.nx).\n" | ||
| 78 | ":param dx: velocity vector (dim state.ndx).\n" | ||
| 79 | ":param firstsecond: derivative w.r.t x or dx or both\n" | ||
| 80 | ":return the partial derivative(s) of the integrate(x, dx) " | ||
| 81 | "function") | ||
| 82 | 
        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("JintegrateTransport", | 
| 83 | pure_virtual(&State::JintegrateTransport_wrap), | ||
| 84 | bp::args("self", "x", "dx", "Jin", "firstsecond"), | ||
| 85 | "Parallel transport from integrate(x, dx) to x.\n\n" | ||
| 86 | "This function performs the parallel transportation of an input " | ||
| 87 | "matrix whose columns are expressed in the tangent space at " | ||
| 88 | "integrate(x, dx) to the tangent space at x point\n" | ||
| 89 | ":param x: state point (dim. state.nx).\n" | ||
| 90 | ":param dx: velocity vector (dim state.ndx).\n" | ||
| 91 | ":param Jin: input matrix (number of rows = state.nv).\n" | ||
| 92 | ":param firstsecond: derivative w.r.t x or dx") | ||
| 93 | 
        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 | .add_property( | 
| 94 | "nx", bp::make_function(&State::get_nx), | ||
| 95 | 40 | bp::make_setter(&State::nx_, bp::return_internal_reference<>()), | |
| 96 | "dimension of state tuple") | ||
| 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. 
         | 
      80 | .add_property( | 
| 98 | "ndx", bp::make_function(&State::get_ndx), | ||
| 99 | 40 | bp::make_setter(&State::ndx_, bp::return_internal_reference<>()), | |
| 100 | "dimension of the tangent space of the state manifold") | ||
| 101 | 
        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 | .add_property( | 
| 102 | "nq", bp::make_function(&State::get_nq), | ||
| 103 | 40 | bp::make_setter(&State::nq_, bp::return_internal_reference<>()), | |
| 104 | "dimension of the configuration tuple") | ||
| 105 | 
        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 | .add_property( | 
| 106 | "nv", bp::make_function(&State::get_nv), | ||
| 107 | 40 | bp::make_setter(&State::nv_, bp::return_internal_reference<>()), | |
| 108 | "dimension of tangent space of the configuration manifold") | ||
| 109 | 
        2/4✓ Branch 1 taken 20 times. 
          ✗ Branch 2 not taken. 
          ✓ Branch 4 taken 20 times. 
          ✗ Branch 5 not taken. 
         | 
      80 | .add_property("has_limits", bp::make_function(&State::get_has_limits), | 
| 110 | "indicates whether problem has finite state limits") | ||
| 111 | 
        1/2✓ Branch 1 taken 20 times. 
          ✗ Branch 2 not taken. 
         | 
      40 | .add_property( | 
| 112 | "lb", | ||
| 113 | 40 | bp::make_getter(&State::lb_, bp::return_internal_reference<>()), | |
| 114 | &State::set_lb, "lower state limits") | ||
| 115 | 
        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 | .add_property( | 
| 116 | "ub", | ||
| 117 | 40 | bp::make_getter(&State::ub_, bp::return_internal_reference<>()), | |
| 118 | &State::set_ub, "upper state limits"); | ||
| 119 | 40 | } | |
| 120 | }; | ||
| 121 | |||
| 122 | #define CROCODDYL_STATE_ABSTRACT_PYTHON_BINDINGS(Scalar) \ | ||
| 123 | typedef StateAbstractTpl<Scalar> State; \ | ||
| 124 | typedef StateAbstractTpl_wrap<Scalar> State_wrap; \ | ||
| 125 | bp::register_ptr_to_python<std::shared_ptr<State>>(); \ | ||
| 126 | bp::class_<State_wrap, boost::noncopyable>( \ | ||
| 127 | "StateAbstract", \ | ||
| 128 | "Abstract class for the state representation.\n\n" \ | ||
| 129 | "A state is represented by its operators: difference, integrates and " \ | ||
| 130 | "their derivatives. The difference operator returns the value of x1 " \ | ||
| 131 | "[-] x0 operation. Instead the integrate operator returns the value of " \ | ||
| 132 | "x [+] dx. These operators are used to compared two points on the " \ | ||
| 133 | "state manifold M or to advance the state given a tangential velocity " \ | ||
| 134 | "(Tx M). Therefore the points x, x0 and x1 belong to the manifold M; " \ | ||
| 135 | "and dx or x1 [-] x0 lie on its tangential space") \ | ||
| 136 | .def(StateAbstractVisitor<State_wrap>()) \ | ||
| 137 | .def(PrintableVisitor<State_wrap>()) \ | ||
| 138 | .def(CopyableVisitor<State_wrap>()); | ||
| 139 | |||
| 140 | 10 | void exposeStateAbstract() { | |
| 141 | 20 | bp::enum_<Jcomponent>("Jcomponent") | |
| 142 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .value("both", both) | 
| 143 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .value("first", first) | 
| 144 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .export_values() | 
| 145 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .value("second", second); | 
| 146 | |||
| 147 | 20 | bp::enum_<AssignmentOp>("AssignmentOp") | |
| 148 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .value("setto", setto) | 
| 149 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .value("addto", addto) | 
| 150 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .value("rmfrom", rmfrom) | 
| 151 | 
        1/2✓ Branch 1 taken 10 times. 
          ✗ Branch 2 not taken. 
         | 
      10 | .export_values(); | 
| 152 | |||
| 153 | 
        11/22✓ 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 14 taken 10 times. 
          ✗ Branch 15 not taken. 
          ✓ Branch 17 taken 10 times. 
          ✗ Branch 18 not taken. 
          ✓ Branch 20 taken 10 times. 
          ✗ Branch 21 not taken. 
          ✓ Branch 25 taken 10 times. 
          ✗ Branch 26 not taken. 
          ✓ Branch 28 taken 10 times. 
          ✗ Branch 29 not taken. 
          ✓ Branch 31 taken 10 times. 
          ✗ Branch 32 not taken. 
          ✓ Branch 34 taken 10 times. 
          ✗ Branch 35 not taken. 
          ✓ Branch 37 taken 10 times. 
          ✗ Branch 38 not taken. 
         | 
      20 | CROCODDYL_PYTHON_SCALARS(CROCODDYL_STATE_ABSTRACT_PYTHON_BINDINGS) | 
| 154 | 10 | } | |
| 155 | |||
| 156 | } // namespace python | ||
| 157 | } // namespace crocoddyl | ||
| 158 |