Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2022-2023, Heriot-Watt University |
5 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
6 |
|
|
// All rights reserved. |
7 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
8 |
|
|
|
9 |
|
|
// Auto-generated file for double |
10 |
|
|
#include "crocoddyl/core/residuals/joint-acceleration.hpp" |
11 |
|
|
|
12 |
|
|
#include "python/crocoddyl/core/core.hpp" |
13 |
|
|
|
14 |
|
|
namespace crocoddyl { |
15 |
|
|
namespace python { |
16 |
|
|
|
17 |
|
|
template <typename Model> |
18 |
|
|
struct ResidualModelJointAccelerationVisitor |
19 |
|
|
: public bp::def_visitor<ResidualModelJointAccelerationVisitor<Model>> { |
20 |
|
|
typedef typename Model::ResidualDataAbstract Data; |
21 |
|
|
typedef typename Model::Base ModelBase; |
22 |
|
|
typedef typename Model::StateAbstract State; |
23 |
|
|
typedef typename Model::VectorXs VectorXs; |
24 |
|
|
template <class PyClass> |
25 |
|
✗ |
void visit(PyClass& cl) const { |
26 |
|
✗ |
cl.def(bp::init<std::shared_ptr<State>, VectorXs>( |
27 |
|
|
bp::args("self", "state", "aref"), |
28 |
|
|
"Initialize the joint-acceleration residual model.\n\n" |
29 |
|
|
"The default nu value is obtained from state.nv.\n" |
30 |
|
|
":param state: state description\n" |
31 |
|
|
":param aref: reference joint acceleration")) |
32 |
|
✗ |
.def(bp::init<std::shared_ptr<State>, std::size_t>( |
33 |
|
|
bp::args("self", "state", "nu"), |
34 |
|
|
"Initialize the joint-acceleration residual model.\n\n" |
35 |
|
|
"The default reference joint-acceleration is obtained from " |
36 |
|
|
"np.zero(actuation.nu).\n" |
37 |
|
|
":param state: state description\n" |
38 |
|
|
":param nu: dimension of the control vector")) |
39 |
|
✗ |
.def(bp::init<std::shared_ptr<State>>( |
40 |
|
|
bp::args("self", "state"), |
41 |
|
|
"Initialize the joint-acceleration residual model.\n\n" |
42 |
|
|
"The default reference joint-acceleration is obtained from " |
43 |
|
|
"np.zero(actuation.nu). The default nu value is obtained from " |
44 |
|
|
"state.nv.\n" |
45 |
|
|
":param state: state description")) |
46 |
|
✗ |
.def( |
47 |
|
|
"calc", |
48 |
|
|
static_cast<void (Model::*)( |
49 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
50 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
51 |
|
|
bp::args("self", "data", "x", "u"), |
52 |
|
|
"Compute the joint-acceleration residual.\n\n" |
53 |
|
|
":param data: residual data\n" |
54 |
|
|
":param x: state point (dim. state.nx)\n" |
55 |
|
|
":param u: control input (dim. nu)") |
56 |
|
✗ |
.def("calc", |
57 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
58 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
59 |
|
|
&Model::calc), |
60 |
|
|
bp::args("self", "data", "x")) |
61 |
|
✗ |
.def( |
62 |
|
|
"calcDiff", |
63 |
|
|
static_cast<void (Model::*)( |
64 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
65 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
66 |
|
|
bp::args("self", "data", "x", "u"), |
67 |
|
|
"Compute the Jacobians of the joint-acceleration residual.\n\n" |
68 |
|
|
"It assumes that calc has been run first.\n" |
69 |
|
|
":param data: residual data\n" |
70 |
|
|
":param x: state point (dim. state.nx)\n" |
71 |
|
|
":param u: control input (dim. nu)") |
72 |
|
✗ |
.def( |
73 |
|
|
"calcDiff", |
74 |
|
|
static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&, |
75 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
76 |
|
|
&ModelBase::calcDiff), |
77 |
|
|
bp::args("self", "data", "x")) |
78 |
|
✗ |
.def("createData", &Model::createData, |
79 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
80 |
|
|
bp::args("self", "data"), |
81 |
|
|
"Create the joint-acceleration residual data.\n\n" |
82 |
|
|
"Each residual model has its own data that needs to be allocated. " |
83 |
|
|
"This function\n" |
84 |
|
|
"returns the allocated data for the joint-acceleration residual.\n" |
85 |
|
|
":param data: shared data\n" |
86 |
|
|
":return residual data.") |
87 |
|
✗ |
.add_property("reference", |
88 |
|
|
bp::make_function(&Model::get_reference, |
89 |
|
✗ |
bp::return_internal_reference<>()), |
90 |
|
|
&Model::set_reference, "reference joint acceleration"); |
91 |
|
|
} |
92 |
|
|
}; |
93 |
|
|
|
94 |
|
|
#define CROCODDYL_RESIDUAL_MODEL_JOINTACC_PYTHON_BINDINGS(Scalar) \ |
95 |
|
|
typedef ResidualModelJointAccelerationTpl<Scalar> Model; \ |
96 |
|
|
typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ |
97 |
|
|
typedef typename ModelBase::StateAbstract State; \ |
98 |
|
|
typedef typename ModelBase::VectorXs VectorXs; \ |
99 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
100 |
|
|
bp::class_<Model, bp::bases<ModelBase>>( \ |
101 |
|
|
"ResidualModelJointAcceleration", \ |
102 |
|
|
"This residual function defines a residual vector as r = a - aref, " \ |
103 |
|
|
"with a and aref as the current and reference joint acceleration " \ |
104 |
|
|
"(i.e., generalized acceleration), respectively.", \ |
105 |
|
|
bp::init<std::shared_ptr<State>, VectorXs, std::size_t>( \ |
106 |
|
|
bp::args("self", "state", "aref", "nu"), \ |
107 |
|
|
"Initialize the joint-acceleration residual model.\n\n" \ |
108 |
|
|
":param state: state description\n" \ |
109 |
|
|
":param aref: reference joint acceleration\n" \ |
110 |
|
|
":param nu: dimension of the control vector")) \ |
111 |
|
|
.def(ResidualModelJointAccelerationVisitor<Model>()) \ |
112 |
|
|
.def(CastVisitor<Model>()) \ |
113 |
|
|
.def(PrintableVisitor<Model>()) \ |
114 |
|
|
.def(CopyableVisitor<Model>()); |
115 |
|
|
|
116 |
|
✗ |
void exposeResidualJointAcceleration() { |
117 |
|
✗ |
CROCODDYL_RESIDUAL_MODEL_JOINTACC_PYTHON_BINDINGS(double) |
118 |
|
|
} |
119 |
|
|
|
120 |
|
|
} // namespace python |
121 |
|
|
} // namespace crocoddyl |
122 |
|
|
|