1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2019-2023, 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/actions/free-fwddyn.hpp" |
11 |
|
|
|
12 |
|
|
#include "python/crocoddyl/core/diff-action-base.hpp" |
13 |
|
|
#include "python/crocoddyl/multibody/multibody.hpp" |
14 |
|
|
#include "python/crocoddyl/utils/copyable.hpp" |
15 |
|
|
|
16 |
|
|
namespace crocoddyl { |
17 |
|
|
namespace python { |
18 |
|
|
|
19 |
|
10 |
void exposeDifferentialActionFreeFwdDynamics() { |
20 |
|
|
bp::register_ptr_to_python< |
21 |
|
10 |
boost::shared_ptr<DifferentialActionModelFreeFwdDynamics> >(); |
22 |
|
|
|
23 |
✓✗ |
10 |
bp::class_<DifferentialActionModelFreeFwdDynamics, |
24 |
|
|
bp::bases<DifferentialActionModelAbstract> >( |
25 |
|
|
"DifferentialActionModelFreeFwdDynamics", |
26 |
|
|
"Differential action model for free forward dynamics in multibody " |
27 |
|
|
"systems.\n\n" |
28 |
|
|
"This class implements a the dynamics using Articulate Body Algorithm " |
29 |
|
|
"(ABA),\n" |
30 |
|
|
"or a custom implementation in case of system with armatures. If you " |
31 |
|
|
"want to\n" |
32 |
|
|
"include the armature, you need to use set_armature(). On the other " |
33 |
|
|
"hand, the\n" |
34 |
|
|
"stack of cost functions are implemented in CostModelSum().", |
35 |
✓✗ |
10 |
bp::init<boost::shared_ptr<StateMultibody>, |
36 |
|
|
boost::shared_ptr<ActuationModelAbstract>, |
37 |
|
|
boost::shared_ptr<CostModelSum>, |
38 |
|
|
bp::optional<boost::shared_ptr<ConstraintModelManager> > >( |
39 |
|
20 |
bp::args("self", "state", "actuation", "costs", "constraints"), |
40 |
|
|
"Initialize the free forward-dynamics action model.\n\n" |
41 |
|
|
":param state: multibody state\n" |
42 |
|
|
":param actuation: abstract actuation model\n" |
43 |
|
|
":param costs: stack of cost functions\n" |
44 |
|
|
":param constraints: stack of constraint functions")) |
45 |
|
|
.def<void (DifferentialActionModelFreeFwdDynamics::*)( |
46 |
|
|
const boost::shared_ptr<DifferentialActionDataAbstract>&, |
47 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&, |
48 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
49 |
|
|
"calc", &DifferentialActionModelFreeFwdDynamics::calc, |
50 |
✓✗ |
20 |
bp::args("self", "data", "x", "u"), |
51 |
|
|
"Compute the next state and cost value.\n\n" |
52 |
|
|
"It describes the time-continuous evolution of the multibody system " |
53 |
|
|
"without any contact.\n" |
54 |
|
|
"Additionally it computes the cost value associated to this state " |
55 |
|
|
"and control pair.\n" |
56 |
|
|
":param data: free forward-dynamics action data\n" |
57 |
|
|
":param x: time-continuous state vector\n" |
58 |
|
20 |
":param u: time-continuous control input") |
59 |
|
|
.def<void (DifferentialActionModelFreeFwdDynamics::*)( |
60 |
|
|
const boost::shared_ptr<DifferentialActionDataAbstract>&, |
61 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
62 |
|
|
"calc", &DifferentialActionModelAbstract::calc, |
63 |
✓✗✓✗
|
20 |
bp::args("self", "data", "x")) |
64 |
|
|
.def<void (DifferentialActionModelFreeFwdDynamics::*)( |
65 |
|
|
const boost::shared_ptr<DifferentialActionDataAbstract>&, |
66 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&, |
67 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
68 |
|
|
"calcDiff", &DifferentialActionModelFreeFwdDynamics::calcDiff, |
69 |
✓✗ |
20 |
bp::args("self", "data", "x", "u"), |
70 |
|
|
"Compute the derivatives of the differential multibody system (free " |
71 |
|
|
"of contact) and\n" |
72 |
|
|
"its cost functions.\n\n" |
73 |
|
|
"It computes the partial derivatives of the differential multibody " |
74 |
|
|
"system and the\n" |
75 |
|
|
"cost function. It assumes that calc has been run first.\n" |
76 |
|
|
"This function builds a quadratic approximation of the\n" |
77 |
|
|
"action model (i.e. dynamical system and cost function).\n" |
78 |
|
|
":param data: free forward-dynamics action data\n" |
79 |
|
|
":param x: time-continuous state vector\n" |
80 |
✓✗ |
10 |
":param u: time-continuous control input\n") |
81 |
|
|
.def<void (DifferentialActionModelFreeFwdDynamics::*)( |
82 |
|
|
const boost::shared_ptr<DifferentialActionDataAbstract>&, |
83 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
84 |
|
|
"calcDiff", &DifferentialActionModelAbstract::calcDiff, |
85 |
✓✗✓✗
|
20 |
bp::args("self", "data", "x")) |
86 |
|
|
.def("createData", &DifferentialActionModelFreeFwdDynamics::createData, |
87 |
✓✗ |
20 |
bp::args("self"), |
88 |
✓✗✓✗
|
20 |
"Create the free forward dynamics differential action data.") |
89 |
|
|
.add_property("pinocchio", |
90 |
✓✗ |
10 |
bp::make_function( |
91 |
|
|
&DifferentialActionModelFreeFwdDynamics::get_pinocchio, |
92 |
|
10 |
bp::return_internal_reference<>()), |
93 |
✓✗ |
10 |
"multibody model (i.e. pinocchio model)") |
94 |
|
|
.add_property("actuation", |
95 |
✓✗ |
10 |
bp::make_function( |
96 |
|
|
&DifferentialActionModelFreeFwdDynamics::get_actuation, |
97 |
|
10 |
bp::return_value_policy<bp::return_by_value>()), |
98 |
✓✗ |
10 |
"actuation model") |
99 |
|
|
.add_property( |
100 |
|
|
"costs", |
101 |
✓✗ |
10 |
bp::make_function(&DifferentialActionModelFreeFwdDynamics::get_costs, |
102 |
|
10 |
bp::return_value_policy<bp::return_by_value>()), |
103 |
✓✗ |
10 |
"total cost model") |
104 |
|
|
.add_property( |
105 |
|
|
"constraints", |
106 |
✓✗ |
10 |
bp::make_function( |
107 |
|
|
&DifferentialActionModelFreeFwdDynamics::get_constraints, |
108 |
|
10 |
bp::return_value_policy<bp::return_by_value>()), |
109 |
✓✗ |
10 |
"constraint model manager") |
110 |
|
|
.add_property("armature", |
111 |
✓✗ |
10 |
bp::make_function( |
112 |
|
|
&DifferentialActionModelFreeFwdDynamics::get_armature, |
113 |
|
|
bp::return_internal_reference<>()), |
114 |
✓✗ |
20 |
bp::make_function( |
115 |
|
|
&DifferentialActionModelFreeFwdDynamics::set_armature), |
116 |
✓✗ |
10 |
"set an armature mechanism in the joints") |
117 |
✓✗ |
10 |
.def(CopyableVisitor<DifferentialActionModelFreeFwdDynamics>()); |
118 |
|
|
|
119 |
|
|
bp::register_ptr_to_python< |
120 |
|
10 |
boost::shared_ptr<DifferentialActionDataFreeFwdDynamics> >(); |
121 |
|
|
|
122 |
✓✗ |
10 |
bp::class_<DifferentialActionDataFreeFwdDynamics, |
123 |
|
|
bp::bases<DifferentialActionDataAbstract> >( |
124 |
|
|
"DifferentialActionDataFreeFwdDynamics", |
125 |
|
|
"Action data for the free forward dynamics system.", |
126 |
✓✗ |
10 |
bp::init<DifferentialActionModelFreeFwdDynamics*>( |
127 |
|
20 |
bp::args("self", "model"), |
128 |
|
|
"Create free forward-dynamics action data.\n\n" |
129 |
|
|
":param model: free forward-dynamics action model")) |
130 |
|
|
.add_property( |
131 |
|
|
"pinocchio", |
132 |
✓✗ |
10 |
bp::make_getter(&DifferentialActionDataFreeFwdDynamics::pinocchio, |
133 |
|
10 |
bp::return_internal_reference<>()), |
134 |
✓✗ |
10 |
"pinocchio data") |
135 |
|
|
.add_property( |
136 |
|
|
"multibody", |
137 |
✓✗ |
10 |
bp::make_getter(&DifferentialActionDataFreeFwdDynamics::multibody, |
138 |
|
10 |
bp::return_internal_reference<>()), |
139 |
✓✗ |
10 |
"multibody data") |
140 |
|
|
.add_property( |
141 |
|
|
"costs", |
142 |
✓✗ |
10 |
bp::make_getter(&DifferentialActionDataFreeFwdDynamics::costs, |
143 |
|
10 |
bp::return_value_policy<bp::return_by_value>()), |
144 |
✓✗ |
10 |
"total cost data") |
145 |
|
|
.add_property( |
146 |
|
|
"constraints", |
147 |
✓✗ |
10 |
bp::make_getter(&DifferentialActionDataFreeFwdDynamics::constraints, |
148 |
|
10 |
bp::return_value_policy<bp::return_by_value>()), |
149 |
✓✗ |
10 |
"constraint data") |
150 |
|
|
.add_property( |
151 |
|
|
"Minv", |
152 |
✓✗ |
10 |
bp::make_getter(&DifferentialActionDataFreeFwdDynamics::Minv, |
153 |
|
10 |
bp::return_internal_reference<>()), |
154 |
✓✗ |
10 |
"inverse of the joint-space inertia matrix") |
155 |
|
|
.add_property( |
156 |
|
|
"u_drift", |
157 |
✓✗ |
10 |
bp::make_getter(&DifferentialActionDataFreeFwdDynamics::u_drift, |
158 |
|
10 |
bp::return_internal_reference<>()), |
159 |
|
|
"force-bias vector that accounts for control, Coriolis and " |
160 |
✓✗ |
10 |
"gravitational effects") |
161 |
✓✗ |
10 |
.def(CopyableVisitor<DifferentialActionDataFreeFwdDynamics>()); |
162 |
|
10 |
} |
163 |
|
|
|
164 |
|
|
} // namespace python |
165 |
|
|
} // namespace crocoddyl |