1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2019-2024, 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 |
|
|
#ifndef BINDINGS_PYTHON_CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_ |
11 |
|
|
#define BINDINGS_PYTHON_CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_ |
12 |
|
|
|
13 |
|
|
#include "crocoddyl/core/diff-action-base.hpp" |
14 |
|
|
#include "crocoddyl/core/utils/exception.hpp" |
15 |
|
|
#include "python/crocoddyl/core/core.hpp" |
16 |
|
|
|
17 |
|
|
namespace crocoddyl { |
18 |
|
|
namespace python { |
19 |
|
|
|
20 |
|
|
class DifferentialActionModelAbstract_wrap |
21 |
|
|
: public DifferentialActionModelAbstract, |
22 |
|
|
public bp::wrapper<DifferentialActionModelAbstract> { |
23 |
|
|
public: |
24 |
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
25 |
|
|
using DifferentialActionModelAbstract::unone_; |
26 |
|
|
|
27 |
|
5 |
DifferentialActionModelAbstract_wrap(boost::shared_ptr<StateAbstract> state, |
28 |
|
|
const std::size_t nu, |
29 |
|
|
const std::size_t nr = 1, |
30 |
|
|
const std::size_t ng = 0, |
31 |
|
|
const std::size_t nh = 0) |
32 |
|
5 |
: DifferentialActionModelAbstract(state, nu, nr, ng, nh), |
33 |
✓✗ |
5 |
bp::wrapper<DifferentialActionModelAbstract>() { |
34 |
✓✗✓✗ ✓✗ |
5 |
unone_ = NAN * MathBase::VectorXs::Ones(nu); |
35 |
|
5 |
} |
36 |
|
|
|
37 |
|
144 |
void calc(const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
38 |
|
|
const Eigen::Ref<const Eigen::VectorXd>& x, |
39 |
|
|
const Eigen::Ref<const Eigen::VectorXd>& u) { |
40 |
✗✓ |
144 |
if (static_cast<std::size_t>(x.size()) != state_->get_nx()) { |
41 |
|
|
throw_pretty("Invalid argument: " |
42 |
|
|
<< "x has wrong dimension (it should be " + |
43 |
|
|
std::to_string(state_->get_nx()) + ")"); |
44 |
|
|
} |
45 |
✗✓ |
144 |
if (static_cast<std::size_t>(u.size()) != nu_) { |
46 |
|
|
throw_pretty("Invalid argument: " |
47 |
|
|
<< "u has wrong dimension (it should be " + |
48 |
|
|
std::to_string(nu_) + ")"); |
49 |
|
|
} |
50 |
✓✓ |
144 |
if (std::isnan(u.lpNorm<Eigen::Infinity>())) { |
51 |
✓✗✓✗
|
3 |
return bp::call<void>(this->get_override("calc").ptr(), data, |
52 |
|
6 |
(Eigen::VectorXd)x); |
53 |
|
|
} else { |
54 |
✓✗✓✗
|
141 |
return bp::call<void>(this->get_override("calc").ptr(), data, |
55 |
✓✗ |
282 |
(Eigen::VectorXd)x, (Eigen::VectorXd)u); |
56 |
|
|
} |
57 |
|
|
} |
58 |
|
|
|
59 |
|
95 |
void calcDiff(const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
60 |
|
|
const Eigen::Ref<const Eigen::VectorXd>& x, |
61 |
|
|
const Eigen::Ref<const Eigen::VectorXd>& u) { |
62 |
✗✓ |
95 |
if (static_cast<std::size_t>(x.size()) != state_->get_nx()) { |
63 |
|
|
throw_pretty("Invalid argument: " |
64 |
|
|
<< "x has wrong dimension (it should be " + |
65 |
|
|
std::to_string(state_->get_nx()) + ")"); |
66 |
|
|
} |
67 |
✗✓ |
95 |
if (static_cast<std::size_t>(u.size()) != nu_) { |
68 |
|
|
throw_pretty("Invalid argument: " |
69 |
|
|
<< "u has wrong dimension (it should be " + |
70 |
|
|
std::to_string(nu_) + ")"); |
71 |
|
|
} |
72 |
✓✓ |
95 |
if (std::isnan(u.lpNorm<Eigen::Infinity>())) { |
73 |
✓✗✓✗
|
1 |
return bp::call<void>(this->get_override("calcDiff").ptr(), data, |
74 |
|
2 |
(Eigen::VectorXd)x); |
75 |
|
|
} else { |
76 |
✓✗✓✗
|
94 |
return bp::call<void>(this->get_override("calcDiff").ptr(), data, |
77 |
✓✗ |
188 |
(Eigen::VectorXd)x, (Eigen::VectorXd)u); |
78 |
|
|
} |
79 |
|
|
} |
80 |
|
|
|
81 |
|
214 |
boost::shared_ptr<DifferentialActionDataAbstract> createData() { |
82 |
|
214 |
enableMultithreading() = false; |
83 |
✓✗✓✗ ✓✗ |
214 |
if (boost::python::override createData = this->get_override("createData")) { |
84 |
|
|
return bp::call<boost::shared_ptr<DifferentialActionDataAbstract> >( |
85 |
✓✗ |
214 |
createData.ptr()); |
86 |
|
|
} |
87 |
|
|
return DifferentialActionModelAbstract::createData(); |
88 |
|
|
} |
89 |
|
|
|
90 |
|
|
boost::shared_ptr<DifferentialActionDataAbstract> default_createData() { |
91 |
|
|
return this->DifferentialActionModelAbstract::createData(); |
92 |
|
|
} |
93 |
|
|
|
94 |
|
|
void quasiStatic( |
95 |
|
|
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
96 |
|
|
Eigen::Ref<Eigen::VectorXd> u, const Eigen::Ref<const Eigen::VectorXd>& x, |
97 |
|
|
const std::size_t maxiter, const double tol) { |
98 |
|
|
if (boost::python::override quasiStatic = |
99 |
|
|
this->get_override("quasiStatic")) { |
100 |
|
|
u = bp::call<Eigen::VectorXd>(quasiStatic.ptr(), data, (Eigen::VectorXd)x, |
101 |
|
|
maxiter, tol); |
102 |
|
|
if (static_cast<std::size_t>(u.size()) != nu_) { |
103 |
|
|
throw_pretty("Invalid argument: " |
104 |
|
|
<< "u has wrong dimension (it should be " + |
105 |
|
|
std::to_string(nu_) + ")"); |
106 |
|
|
} |
107 |
|
|
return; |
108 |
|
|
} |
109 |
|
|
return DifferentialActionModelAbstract::quasiStatic(data, u, x, maxiter, |
110 |
|
|
tol); |
111 |
|
|
} |
112 |
|
|
|
113 |
|
|
void default_quasiStatic( |
114 |
|
|
const boost::shared_ptr<DifferentialActionDataAbstract>& data, |
115 |
|
|
Eigen::Ref<Eigen::VectorXd> u, const Eigen::Ref<const Eigen::VectorXd>& x, |
116 |
|
|
const std::size_t maxiter, const double tol) { |
117 |
|
|
return this->DifferentialActionModelAbstract::quasiStatic(data, u, x, |
118 |
|
|
maxiter, tol); |
119 |
|
|
} |
120 |
|
|
}; |
121 |
|
|
|
122 |
|
20 |
BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS( |
123 |
|
|
DifferentialActionModel_quasiStatic_wraps, |
124 |
|
|
DifferentialActionModelAbstract::quasiStatic_x, 2, 4) |
125 |
|
|
|
126 |
|
|
} // namespace python |
127 |
|
|
} // namespace crocoddyl |
128 |
|
|
|
129 |
|
|
#endif // BINDINGS_PYTHON_CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_ |