Directory: | ./ |
---|---|
File: | bindings/python/crocoddyl/multibody/states/multibody.cpp |
Date: | 2025-03-26 19:23:43 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 18 | 18 | 100.0% |
Branches: | 37 | 74 | 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/multibody/states/multibody.hpp" | ||
11 | |||
12 | #include "python/crocoddyl/core/state-base.hpp" | ||
13 | #include "python/crocoddyl/multibody/multibody.hpp" | ||
14 | |||
15 | namespace crocoddyl { | ||
16 | namespace python { | ||
17 | |||
18 | template <typename State> | ||
19 | struct StateMultibodyVisitor | ||
20 | : public bp::def_visitor<StateMultibodyVisitor<State>> { | ||
21 | typedef typename State::Scalar Scalar; | ||
22 | 50 | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(Jdiffs, | |
23 | StateAbstractTpl<Scalar>::Jdiff_Js, 2, | ||
24 | 3) | ||
25 | 74 | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS( | |
26 | Jintegrates, StateAbstractTpl<Scalar>::Jintegrate_Js, 2, 3) | ||
27 | template <class PyClass> | ||
28 | 40 | void visit(PyClass& cl) const { | |
29 | 40 | cl.def("zero", &State::zero, bp::args("self"), | |
30 | "Return the neutral robot configuration with zero velocity.\n\n" | ||
31 | ":return neutral robot configuration with zero velocity") | ||
32 |
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"), |
33 | "Return a random reference state.\n\n" | ||
34 | ":return random reference state") | ||
35 |
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"), |
36 | "Operator that differentiates the two robot states.\n\n" | ||
37 | "It returns the value of x1 [-] x0 operation. This operator uses " | ||
38 | "the Lie algebra since the robot's root could lie in the SE(3) " | ||
39 | "manifold.\n" | ||
40 | ":param x0: current state (dim state.nx()).\n" | ||
41 | ":param x1: next state (dim state.nx()).\n" | ||
42 | ":return x1 - x0 value (dim state.nx()).") | ||
43 |
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"), |
44 | "Operator that integrates the current robot state.\n\n" | ||
45 | "It returns the value of x [+] dx operation. This operator uses " | ||
46 | "the Lie algebra since the robot's root could lie in the SE(3) " | ||
47 | "manifold. Futhermore there is no timestep here (i.e. dx = v*dt), " | ||
48 | "note this if you're integrating a velocity v during an interval " | ||
49 | "dt.\n" | ||
50 | ":param x: current state (dim state.nx()).\n" | ||
51 | ":param dx: displacement of the state (dim state.ndx()).\n" | ||
52 | ":return x + dx value (dim state.nx()).") | ||
53 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | .def("Jdiff", &State::Jdiff_Js, |
54 |
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"), |
55 | "Compute the partial derivatives of the diff operator.\n\n" | ||
56 | "Both Jacobian matrices are represented throught an " | ||
57 | "identity matrix, with the exception that the robot's root " | ||
58 | "is defined as free-flying joint (SE(3)). By default, this " | ||
59 | "function returns the derivatives of the first and second " | ||
60 | "argument (i.e. firstsecond='both'). However we ask for a " | ||
61 | "specific partial derivative by setting " | ||
62 | "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. with the exception that the robot's root is defined " | ||
74 | "as free-flying joint (SE(3)). By default, this function " | ||
75 | "returns the derivatives of the first and second argument " | ||
76 | "(i.e. firstsecond='both'). However we ask for a specific " | ||
77 | "partial derivative by setting firstsecond='first' or " | ||
78 | "firstsecond='second'.\n" | ||
79 | ":param x: current state (dim state.nx()).\n" | ||
80 | ":param dx: displacement of the state (dim state.ndx()).\n" | ||
81 | ":param firstsecond: derivative w.r.t x or dx or both\n" | ||
82 | ":return the partial derivative(s) of the integrate(x, dx) " | ||
83 | "function")) | ||
84 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("JintegrateTransport", &State::JintegrateTransport, |
85 | bp::args("self", "x", "dx", "Jin", "firstsecond"), | ||
86 | "Parallel transport from integrate(x, dx) to x.\n\n" | ||
87 | "This function performs the parallel transportation of an input " | ||
88 | "matrix whose columns are expressed in the tangent space at " | ||
89 | "integrate(x, dx) to the tangent space at x point\n" | ||
90 | ":param x: state point (dim. state.nx).\n" | ||
91 | ":param dx: velocity vector (dim state.ndx).\n" | ||
92 | ":param Jin: input matrix (number of rows = state.nv).\n" | ||
93 | ":param firstsecond: derivative w.r.t x or dx") | ||
94 |
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( |
95 | "pinocchio", | ||
96 | bp::make_function(&State::get_pinocchio, | ||
97 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
98 | "pinocchio model"); | ||
99 | 40 | } | |
100 | }; | ||
101 | |||
102 | #define CROCODDYL_STATE_MULTIBODY_PYTHON_BINDINGS(Scalar) \ | ||
103 | typedef StateMultibodyTpl<Scalar> State; \ | ||
104 | typedef StateAbstractTpl<Scalar> StateBase; \ | ||
105 | typedef pinocchio::ModelTpl<Scalar> Model; \ | ||
106 | bp::register_ptr_to_python<std::shared_ptr<State>>(); \ | ||
107 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
108 | bp::class_<State, bp::bases<StateBase>>( \ | ||
109 | "StateMultibody", \ | ||
110 | "Multibody state defined using Pinocchio.\n\n" \ | ||
111 | "Pinocchio defines operators for integrating or differentiating the " \ | ||
112 | "robot's configuration space. And here we assume that the state is " \ | ||
113 | "defined by the robot's configuration and its joint velocities " \ | ||
114 | "(x=[q,v]). Generally speaking, q lies on the manifold configuration " \ | ||
115 | "manifold (M) and v in its tangent space (Tx M). Additionally the " \ | ||
116 | "Pinocchio allows us to compute analytically the Jacobians for the " \ | ||
117 | "differentiate and integrate operators. Note that this code can be " \ | ||
118 | "reused in any robot that is described through its Pinocchio model.", \ | ||
119 | bp::init<std::shared_ptr<Model>>( \ | ||
120 | bp::args("self", "pinocchio"), \ | ||
121 | "Initialize the multibody state given a Pinocchio model.\n\n" \ | ||
122 | ":param pinocchio: pinocchio model (i.e. multibody model)") \ | ||
123 | [bp::with_custodian_and_ward<1, 2>()]) \ | ||
124 | .def(StateMultibodyVisitor<State>()) \ | ||
125 | .def(CastVisitor<State>()) \ | ||
126 | .def(PrintableVisitor<State>()) \ | ||
127 | .def(CopyableVisitor<State>()); | ||
128 | |||
129 | 10 | void exposeStateMultibody() { | |
130 |
20/40✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 10 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 10 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 10 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 10 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 10 times.
✗ Branch 23 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 39 taken 10 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 10 times.
✗ Branch 43 not taken.
✓ Branch 45 taken 10 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 10 times.
✗ Branch 49 not taken.
✓ Branch 51 taken 10 times.
✗ Branch 52 not taken.
✓ Branch 54 taken 10 times.
✗ Branch 55 not taken.
✓ Branch 57 taken 10 times.
✗ Branch 58 not taken.
✓ Branch 60 taken 10 times.
✗ Branch 61 not taken.
✓ Branch 63 taken 10 times.
✗ Branch 64 not taken.
✓ Branch 66 taken 10 times.
✗ Branch 67 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS(CROCODDYL_STATE_MULTIBODY_PYTHON_BINDINGS) |
131 | 10 | } | |
132 | |||
133 | } // namespace python | ||
134 | } // namespace crocoddyl | ||
135 |