GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/core/numdiff/state-float.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 15 0.0%
Branches: 0 46 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2023, University of Edinburgh, University of Pisa,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 // Auto-generated file for float
11 #include "crocoddyl/core/numdiff/state.hpp"
12
13 #include "python/crocoddyl/core/core.hpp"
14 #include "python/crocoddyl/core/state-base.hpp"
15 #include "python/crocoddyl/utils/copyable.hpp"
16
17 namespace crocoddyl {
18 namespace python {
19
20 template <typename State>
21 struct StateNumDiffVisitor
22 : public bp::def_visitor<StateNumDiffVisitor<State>> {
23 typedef typename State::Scalar Scalar;
24 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(Jdiffs,
25 StateAbstractTpl<Scalar>::Jdiff_Js, 2,
26 3)
27 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(
28 Jintegrates, StateAbstractTpl<Scalar>::Jintegrate_Js, 2, 3)
29 template <class PyClass>
30 void visit(PyClass& cl) const {
31 cl.def("zero", &State::zero, bp::args("self"),
32 "Return a zero reference state.\n\n"
33 ":return zero reference state")
34 .def("rand", &State::rand, bp::args("self"),
35 "Return a random reference state.\n\n"
36 ":return random reference state")
37 .def("diff", &State::diff_dx, bp::args("self", "x0", "x1"),
38 "Operator that differentiates the two state points.\n\n"
39 "It returns the value of x1 [-] x0 operation. Due to a state "
40 "vector lies in the Euclidean space, this operator is defined "
41 "with arithmetic subtraction.\n"
42 ":param x0: current state (dim state.nx).\n"
43 ":param x1: next state (dim state.nx).\n"
44 ":return x1 - x0 value (dim state.nx).")
45 .def("integrate", &State::integrate_x, bp::args("self", "x", "dx"),
46 "Operator that integrates the current state.\n\n"
47 "It returns the value of x [+] dx operation. Due to a state "
48 "vector lies in the Euclidean space, this operator is defined "
49 "with arithmetic addition. Futhermore there is no timestep here "
50 "(i.e. dx = v*dt), note this if you're integrating a velocity v "
51 "during an interval dt.\n"
52 ":param x: current state (dim state.nx).\n"
53 ":param dx: displacement of the state (dim state.nx).\n"
54 ":return x + dx value (dim state.nx).")
55 .def("Jdiff", &State::Jdiff_Js,
56 Jdiffs(bp::args("self", "x0", "x1", "firstsecond"),
57 "Compute the partial derivatives of arithmetic "
58 "substraction.\n\n"
59 "Both Jacobian matrices are represented throught an "
60 "identity matrix, with the exception that the first "
61 "partial derivatives (w.r.t. x0) has negative signed. By "
62 "default, this function returns the derivatives of the "
63 "first and second argument (i.e., firstsecond='both'). "
64 "However we ask for a specific partial derivative by "
65 "setting firstsecond='first' or firstsecond='second'.\n"
66 ":param x0: current state (dim state.nx).\n"
67 ":param x1: next state (dim state.nx).\n"
68 ":param firstsecond: derivative w.r.t x0 or x1 or both\n"
69 ":return the partial derivative(s) of the diff(x0, x1) "
70 "function"))
71 .def("Jintegrate", &State::Jintegrate_Js,
72 Jintegrates(
73 bp::args("self", "x", "dx", "firstsecond"),
74 "Compute the partial derivatives of arithmetic addition.\n\n"
75 "Both Jacobian matrices are represented throught an identity "
76 "matrix. By default, this function returns the derivatives of "
77 "the first and second argument (i.e., firstsecond='both'). "
78 "However we ask for a specific partial derivative by setting "
79 "firstsecond='first' or firstsecond='second'.\n"
80 ":param x: current state (dim state.nx).\n"
81 ":param dx: displacement of the state (dim state.nx).\n"
82 ":param firstsecond: derivative w.r.t x or dx or both\n"
83 ":return the partial derivative(s) of the integrate(x, dx) "
84 "function"))
85 .def("JintegrateTransport", &State::JintegrateTransport,
86 bp::args("self", "x", "dx", "Jin", "firstsecond"),
87 "Parallel transport from integrate(x, dx) to x.\n\n"
88 "This function performs the parallel transportation of an input "
89 "matrix whose columns are expressed in the tangent space at "
90 "integrate(x, dx) to the tangent space at x point.\n"
91 ":param x: state point (dim. state.nx).\n"
92 ":param dx: velocity vector (dim state.ndx).\n"
93 ":param Jin: input matrix (number of rows = state.nv).\n"
94 ":param firstsecond: derivative w.r.t x or dx")
95 .add_property(
96 "disturbance", bp::make_function(&State::get_disturbance),
97 &State::set_disturbance,
98 "disturbance constant used in the numerical differentiation");
99 }
100 };
101
102 #define CROCODDYL_STATE_NUMDIFF_PYTHON_BINDINGS(Scalar) \
103 typedef StateNumDiffTpl<Scalar> State; \
104 typedef StateAbstractTpl<Scalar> StateBase; \
105 bp::register_ptr_to_python<std::shared_ptr<State>>(); \
106 bp::class_<State, bp::bases<StateBase>>( \
107 "StateNumDiff", \
108 "Abstract class for computing Jdiff and Jintegrate by using numerical " \
109 "differentiation.\n\n", \
110 bp::init<std::shared_ptr<StateBase>>( \
111 bp::args("self", "state"), \
112 "Initialize the state numdiff.\n\n" \
113 ":param model: state where we compute the derivatives through " \
114 "numerial differentiation")) \
115 .def(StateNumDiffVisitor<State>()) \
116 .def(CastVisitor<State>()) \
117 .def(PrintableVisitor<State>()) \
118 .def(CopyableVisitor<State>());
119
120 void exposeStateNumDiff() {
121 CROCODDYL_STATE_NUMDIFF_PYTHON_BINDINGS(float)
122 }
123
124 } // namespace python
125 } // namespace crocoddyl
126