Directory: | ./ |
---|---|
File: | bindings/python/crocoddyl/core/states/euclidean.cpp |
Date: | 2025-03-26 19:23:43 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 16 | 16 | 100.0% |
Branches: | 32 | 64 | 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/core/states/euclidean.hpp" | ||
11 | |||
12 | #include "python/crocoddyl/core/core.hpp" | ||
13 | #include "python/crocoddyl/core/state-base.hpp" | ||
14 | |||
15 | namespace crocoddyl { | ||
16 | namespace python { | ||
17 | |||
18 | template <typename State> | ||
19 | struct StateVectorVisitor : public bp::def_visitor<StateVectorVisitor<State>> { | ||
20 | typedef typename State::Scalar Scalar; | ||
21 | 42 | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(Jdiffs, | |
22 | StateAbstractTpl<Scalar>::Jdiff_Js, 2, | ||
23 | 3) | ||
24 | 42 | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS( | |
25 | Jintegrates, StateAbstractTpl<Scalar>::Jintegrate_Js, 2, 3) | ||
26 | template <class PyClass> | ||
27 | 40 | void visit(PyClass& cl) const { | |
28 | 40 | cl.def("zero", &State::zero, bp::args("self"), | |
29 | "Return a zero reference state.\n\n" | ||
30 | ":return zero reference state") | ||
31 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("rand", &State::rand, bp::args("self"), |
32 | "Return a random reference state.\n\n" | ||
33 | ":return random reference state") | ||
34 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("diff", &State::diff_dx, bp::args("self", "x0", "x1"), |
35 | "Operator that differentiates the two state points.\n\n" | ||
36 | "It returns the value of x1 [-] x0 operation. Due to a state " | ||
37 | "vector lies in the Euclidean space, this operator is defined " | ||
38 | "with arithmetic subtraction.\n" | ||
39 | ":param x0: current state (dim state.nx()).\n" | ||
40 | ":param x1: next state (dim state.nx()).\n" | ||
41 | ":return x1 - x0 value (dim state.nx()).") | ||
42 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("integrate", &State::integrate_x, bp::args("self", "x", "dx"), |
43 | "Operator that integrates the current state.\n\n" | ||
44 | "It returns the value of x [+] dx operation. Due to a state " | ||
45 | "vector lies in the Euclidean space, this operator is defined " | ||
46 | "with arithmetic addition. Futhermore there is no timestep here " | ||
47 | "(i.e. dx = v*dt), note this if you're integrating a velocity v " | ||
48 | "during an interval dt.\n" | ||
49 | ":param x: current state (dim state.nx()).\n" | ||
50 | ":param dx: displacement of the state (dim state.nx()).\n" | ||
51 | ":return x + dx value (dim state.nx()).") | ||
52 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | .def("Jdiff", &State::Jdiff_Js, |
53 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | Jdiffs(bp::args("self", "x0", "x1", "firstsecond"), |
54 | "Compute the partial derivatives of arithmetic " | ||
55 | "substraction.\n\n" | ||
56 | "Both Jacobian matrices are represented throught an " | ||
57 | "identity matrix, with the exception that the first " | ||
58 | "partial derivatives (w.r.t. x0) has negative signed. By " | ||
59 | "default, this function returns the derivatives of the " | ||
60 | "first and second argument (i.e. firstsecond='both'). " | ||
61 | "However we ask for a specific partial derivative by " | ||
62 | "setting firstsecond='first' or firstsecond='second'.\n" | ||
63 | ":param x0: current state (dim state.nx()).\n" | ||
64 | ":param x1: next state (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) " | ||
67 | "function")) | ||
68 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | .def("Jintegrate", &State::Jintegrate_Js, |
69 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | Jintegrates( |
70 | bp::args("self", "x", "dx", "firstsecond"), | ||
71 | "Compute the partial derivatives of arithmetic addition.\n\n" | ||
72 | "Both Jacobian matrices are represented throught an identity " | ||
73 | "matrix. By default, this function returns the derivatives of " | ||
74 | "the first and second argument (i.e. firstsecond='both'). " | ||
75 | "However we ask for a specific partial derivative by setting " | ||
76 | "firstsecond='first' or firstsecond='second'.\n" | ||
77 | ":param x: current state (dim state.nx()).\n" | ||
78 | ":param dx: displacement of the state (dim state.nx()).\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.
|
40 | .def("JintegrateTransport", &State::JintegrateTransport, |
83 | bp::args("self", "x", "dx", "Jin", "firstsecond"), | ||
84 | "Parallel transport from integrate(x, dx) to x.\n\n" | ||
85 | "This function performs the parallel transportation of an input " | ||
86 | "matrix whose columns are expressed in the tangent space at " | ||
87 | "integrate(x, dx) to the tangent space at x point.\n" | ||
88 | ":param x: state point (dim. state.nx).\n" | ||
89 | ":param dx: velocity vector (dim state.ndx).\n" | ||
90 | ":param Jin: input matrix (number of rows = state.nv).\n" | ||
91 | ":param firstsecond: derivative w.r.t x or dx"); | ||
92 | 40 | } | |
93 | }; | ||
94 | |||
95 | #define CROCODDYL_STATE_VECTOR_PYTHON_BINDINGS(Scalar) \ | ||
96 | typedef StateVectorTpl<Scalar> State; \ | ||
97 | typedef StateAbstractTpl<Scalar> StateBase; \ | ||
98 | bp::register_ptr_to_python<std::shared_ptr<State>>(); \ | ||
99 | bp::class_<State, bp::bases<StateBase>>( \ | ||
100 | "StateVector", \ | ||
101 | "Euclidean state vector.\n\n" \ | ||
102 | "For this type of states, the difference and integrate operators are " \ | ||
103 | "described by arithmetic subtraction and addition operations, " \ | ||
104 | "respectively. Due to the Euclidean point and its velocity lie in the " \ | ||
105 | "same space, all Jacobians are described throught the identity matrix.", \ | ||
106 | bp::init<std::size_t>(bp::args("self", "nx"), \ | ||
107 | "Initialize the vector dimension.\n\n" \ | ||
108 | ":param nx: dimension of state")) \ | ||
109 | .def(StateVectorVisitor<State>()) \ | ||
110 | .def(CastVisitor<State>()) \ | ||
111 | .def(PrintableVisitor<State>()) \ | ||
112 | .def(CopyableVisitor<State>()); | ||
113 | |||
114 | 10 | void exposeStateEuclidean() { | |
115 |
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_STATE_VECTOR_PYTHON_BINDINGS) |
116 | 10 | } | |
117 | |||
118 | } // namespace python | ||
119 | } // namespace crocoddyl | ||
120 |