1 |
|
|
#include <pinocchio/multibody/fwd.hpp> |
2 |
|
|
|
3 |
|
|
#include "aig/dyna_com.hpp" |
4 |
|
|
// Must be included first! |
5 |
|
|
#include <boost/python.hpp> |
6 |
|
|
#include <boost/python/return_internal_reference.hpp> |
7 |
|
|
#include <boost/python/suite/indexing/vector_indexing_suite.hpp> |
8 |
|
|
#include <eigenpy/eigenpy.hpp> |
9 |
|
|
|
10 |
|
|
#include "aig/biped_ig.hpp" |
11 |
|
|
#include "aig/python.hpp" |
12 |
|
|
|
13 |
|
|
namespace aig { |
14 |
|
|
namespace python { |
15 |
|
|
namespace bp = boost::python; |
16 |
|
|
|
17 |
|
|
Eigen::VectorXd solve(BipedIG &self, const Eigen::Vector3d &com, |
18 |
|
|
const pinocchio::SE3 &LF, const pinocchio::SE3 &RF, |
19 |
|
|
const Eigen::VectorXd &q0, |
20 |
|
|
const double &tolerance = 1e-10, |
21 |
|
|
const int &max_iterations = 0) { |
22 |
|
|
Eigen::VectorXd pos; |
23 |
|
|
self.solve(com, LF, RF, q0, pos, tolerance, max_iterations); |
24 |
|
|
return pos; |
25 |
|
|
} |
26 |
|
|
Eigen::VectorXd solve(BipedIG &self, const Eigen::Vector3d &com, |
27 |
|
|
const Eigen::Isometry3d &LF, const Eigen::Isometry3d &RF, |
28 |
|
|
const Eigen::VectorXd &q0, |
29 |
|
|
const double &tolerance = 1e-10, |
30 |
|
|
const int &max_iterations = 0) { |
31 |
|
|
Eigen::VectorXd pos; |
32 |
|
|
self.solve(com, LF, RF, q0, pos, tolerance, max_iterations); |
33 |
|
|
return pos; |
34 |
|
|
} |
35 |
|
|
Eigen::VectorXd solve(BipedIG &self, const Eigen::Vector3d &com, |
36 |
|
|
const Eigen::Matrix3d &baseRotation, |
37 |
|
|
const pinocchio::SE3 &LF, const pinocchio::SE3 &RF, |
38 |
|
|
const Eigen::VectorXd &q0, |
39 |
|
|
const double &tolerance = 1e-10, |
40 |
|
|
const int &max_iterations = 0) { |
41 |
|
|
Eigen::VectorXd pos; |
42 |
|
|
self.solve(com, baseRotation, LF, RF, q0, pos, tolerance, max_iterations); |
43 |
|
|
return pos; |
44 |
|
|
} |
45 |
|
|
Eigen::VectorXd solve(BipedIG &self, const Eigen::Vector3d &com, |
46 |
|
|
const Eigen::Matrix3d &baseRotation, |
47 |
|
|
const Eigen::Isometry3d &LF, const Eigen::Isometry3d &RF, |
48 |
|
|
const Eigen::VectorXd &q0, |
49 |
|
|
const double &tolerance = 1e-10, |
50 |
|
|
const int &max_iterations = 0) { |
51 |
|
|
Eigen::VectorXd pos; |
52 |
|
|
self.solve(com, baseRotation, LF, RF, q0, pos, tolerance, max_iterations); |
53 |
|
|
return pos; |
54 |
|
|
} |
55 |
|
|
Eigen::VectorXd solve(BipedIG &self, const pinocchio::SE3 &base, |
56 |
|
|
const pinocchio::SE3 &LF, const pinocchio::SE3 &RF, |
57 |
|
|
const Eigen::VectorXd &q0) { |
58 |
|
|
Eigen::VectorXd pos; |
59 |
|
|
self.solve(base, LF, RF, q0, pos); |
60 |
|
|
return pos; |
61 |
|
|
} |
62 |
|
|
Eigen::VectorXd solve(BipedIG &self, const Eigen::Isometry3d &base, |
63 |
|
|
const Eigen::Isometry3d &LF, const Eigen::Isometry3d &RF, |
64 |
|
|
const Eigen::VectorXd &q0) { |
65 |
|
|
Eigen::VectorXd pos; |
66 |
|
|
self.solve(base, LF, RF, q0, pos); |
67 |
|
|
return pos; |
68 |
|
|
} |
69 |
|
|
|
70 |
|
|
bp::tuple solve(BipedIG &self, const std::array<Eigen::Vector3d, 3> &com, |
71 |
|
|
const std::array<pinocchio::SE3, 3> &LF, |
72 |
|
|
const std::array<pinocchio::SE3, 3> &RF, |
73 |
|
|
const Eigen::VectorXd &q0, const double &dt, |
74 |
|
|
const double &tolerance = 1e-10, |
75 |
|
|
const int &max_iterations = 0) { |
76 |
|
|
Eigen::VectorXd pos, vel, acc; |
77 |
|
|
self.solve(com, LF, RF, q0, pos, vel, acc, dt, tolerance, max_iterations); |
78 |
|
|
return bp::tuple(pos); |
79 |
|
|
} |
80 |
|
|
bp::tuple solve(BipedIG &self, const std::array<Eigen::Vector3d, 3> &com, |
81 |
|
|
const std::array<Eigen::Isometry3d, 3> &LF, |
82 |
|
|
const std::array<Eigen::Isometry3d, 3> &RF, |
83 |
|
|
const Eigen::VectorXd &q0, const double &dt, |
84 |
|
|
const double &tolerance = 1e-10, |
85 |
|
|
const int &max_iterations = 0) { |
86 |
|
|
Eigen::VectorXd pos, vel, acc; |
87 |
|
|
self.solve(com, LF, RF, q0, pos, vel, acc, dt, tolerance, max_iterations); |
88 |
|
|
return bp::tuple(pos); |
89 |
|
|
} |
90 |
|
|
bp::tuple solve(BipedIG &self, const std::array<Eigen::Vector3d, 3> &com, |
91 |
|
|
const std::array<Eigen::Matrix3d, 3> &baseRotation, |
92 |
|
|
const std::array<pinocchio::SE3, 3> &LF, |
93 |
|
|
const std::array<pinocchio::SE3, 3> &RF, |
94 |
|
|
const Eigen::VectorXd &q0, const double &dt, |
95 |
|
|
const double &tolerance = 1e-10, |
96 |
|
|
const int &max_iterations = 0) { |
97 |
|
|
Eigen::VectorXd pos, vel, acc; |
98 |
|
|
self.solve(com, baseRotation, LF, RF, q0, pos, vel, acc, dt, tolerance, |
99 |
|
|
max_iterations); |
100 |
|
|
return bp::tuple(pos); |
101 |
|
|
} |
102 |
|
|
bp::tuple solve(BipedIG &self, const std::array<Eigen::Vector3d, 3> &com, |
103 |
|
|
const std::array<Eigen::Matrix3d, 3> &baseRotation, |
104 |
|
|
const std::array<Eigen::Isometry3d, 3> &LF, |
105 |
|
|
const std::array<Eigen::Isometry3d, 3> &RF, |
106 |
|
|
const Eigen::VectorXd &q0, const double &dt, |
107 |
|
|
const double &tolerance = 1e-10, |
108 |
|
|
const int &max_iterations = 0) { |
109 |
|
|
Eigen::VectorXd pos, vel, acc; |
110 |
|
|
self.solve(com, baseRotation, LF, RF, q0, pos, vel, acc, dt, tolerance, |
111 |
|
|
max_iterations); |
112 |
|
|
return bp::tuple(pos); |
113 |
|
|
} |
114 |
|
|
bp::tuple solve(BipedIG &self, const bp::list &base, const bp::list &LF, |
115 |
|
|
const bp::list &RF, const Eigen::VectorXd &q0, |
116 |
|
|
const double &dt) { |
117 |
|
|
Eigen::VectorXd pos, vel, acc; |
118 |
|
|
|
119 |
|
|
std::array<pinocchio::SE3, 3> B{bp::extract<pinocchio::SE3>(base[0]), |
120 |
|
|
bp::extract<pinocchio::SE3>(base[1]), |
121 |
|
|
bp::extract<pinocchio::SE3>(base[2])}; |
122 |
|
|
std::array<pinocchio::SE3, 3> L{bp::extract<pinocchio::SE3>(LF[0]), |
123 |
|
|
bp::extract<pinocchio::SE3>(LF[1]), |
124 |
|
|
bp::extract<pinocchio::SE3>(LF[2])}; |
125 |
|
|
std::array<pinocchio::SE3, 3> R{bp::extract<pinocchio::SE3>(RF[0]), |
126 |
|
|
bp::extract<pinocchio::SE3>(RF[1]), |
127 |
|
|
bp::extract<pinocchio::SE3>(RF[2])}; |
128 |
|
|
|
129 |
|
|
self.solve(B, L, R, q0, pos, vel, acc, dt); |
130 |
|
|
|
131 |
|
|
return bp::make_tuple(pos, vel, acc); |
132 |
|
|
} |
133 |
|
|
|
134 |
|
|
bp::tuple solve(BipedIG &self, const std::array<Eigen::Isometry3d, 3> &base, |
135 |
|
|
const std::array<Eigen::Isometry3d, 3> &LF, |
136 |
|
|
const std::array<Eigen::Isometry3d, 3> &RF, |
137 |
|
|
const Eigen::VectorXd &q0, const double &dt) { |
138 |
|
|
Eigen::VectorXd pos, vel, acc; |
139 |
|
|
self.solve(base, LF, RF, q0, pos, vel, acc, dt); |
140 |
|
|
return bp::tuple(pos); |
141 |
|
|
} |
142 |
|
|
|
143 |
|
|
void exposeBiped_IG() { |
144 |
|
|
bp::class_<BipedIGSettings>("BipedIGSettings") |
145 |
|
|
.def_readwrite("left_hip_joint_name", |
146 |
|
|
&BipedIGSettings::left_hip_joint_name) |
147 |
|
|
.def_readwrite("right_hip_joint_name", |
148 |
|
|
&BipedIGSettings::right_hip_joint_name) |
149 |
|
|
.def_readwrite("left_knee_joint_name", |
150 |
|
|
&BipedIGSettings::left_knee_joint_name) |
151 |
|
|
.def_readwrite("right_knee_joint_name", |
152 |
|
|
&BipedIGSettings::right_knee_joint_name) |
153 |
|
|
.def_readwrite("left_ankle_joint_name", |
154 |
|
|
&BipedIGSettings::left_ankle_joint_name) |
155 |
|
|
.def_readwrite("right_ankle_joint_name", |
156 |
|
|
&BipedIGSettings::right_ankle_joint_name) |
157 |
|
|
.def_readwrite("left_foot_frame_name", |
158 |
|
|
&BipedIGSettings::left_foot_frame_name) |
159 |
|
|
.def_readwrite("right_foot_frame_name", |
160 |
|
|
&BipedIGSettings::right_foot_frame_name) |
161 |
|
|
.def("makeSettingsFor", &makeSettingsFor, |
162 |
|
|
bp::args("path_to_robots", "robot_name")) |
163 |
|
|
// .def("__eq__", &BipedIGSettings::operator==) |
164 |
|
|
// .def("__repr__", &BipedIGSettings::operator<<) |
165 |
|
|
; |
166 |
|
|
|
167 |
|
|
bp::class_<LegIGSettings>("LegIGSettings") |
168 |
|
|
.def_readwrite("hip_from_waist", &LegIGSettings::hip_from_waist) |
169 |
|
|
.def_readwrite("knee_from_hip", &LegIGSettings::knee_from_hip) |
170 |
|
|
.def_readwrite("ankle_from_knee", &LegIGSettings::ankle_from_knee) |
171 |
|
|
.def_readwrite("ankle_from_foot", &LegIGSettings::ankle_from_foot); |
172 |
|
|
|
173 |
|
|
bp::class_<BipedIG>("BipedIG", bp::init<>()) |
174 |
|
|
.def("initialize", &BipedIG::initialize, bp::args("self", "settings")) |
175 |
|
|
.def("get_settings", &BipedIG::get_settings, |
176 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
177 |
|
|
bp::args("self")) |
178 |
|
|
.def("getQ0", &BipedIG::getQ0, |
179 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
180 |
|
|
bp::args("self")) |
181 |
|
|
.def("setQ0", &BipedIG::setQ0, bp::args("self", "q0")) |
182 |
|
|
.def<Eigen::VectorXd(BipedIG &, const Eigen::Vector3d &, |
183 |
|
|
const pinocchio::SE3 &, const pinocchio::SE3 &, |
184 |
|
|
const Eigen::VectorXd &, const double &, |
185 |
|
|
const int &)>( |
186 |
|
|
"solve", &solve, |
187 |
|
|
(bp::args("self", "com", "leftFoot", "rightFoot", "q0"), |
188 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
189 |
|
|
.def<Eigen::VectorXd(BipedIG &, const Eigen::Vector3d &, |
190 |
|
|
const Eigen::Isometry3d &, const Eigen::Isometry3d &, |
191 |
|
|
const Eigen::VectorXd &, const double &, |
192 |
|
|
const int &)>( |
193 |
|
|
"solve", &solve, |
194 |
|
|
(bp::args("self", "com", "leftFoot", "rightFoot", "q0"), |
195 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
196 |
|
|
.def<Eigen::VectorXd(BipedIG &, const Eigen::Vector3d &, |
197 |
|
|
const Eigen::Matrix3d &, const pinocchio::SE3 &, |
198 |
|
|
const pinocchio::SE3 &, const Eigen::VectorXd &, |
199 |
|
|
const double &, const int &)>( |
200 |
|
|
"solve", &solve, |
201 |
|
|
(bp::args("self", "com", "baseRotation", "leftFoot", "rightFoot", |
202 |
|
|
"q0"), |
203 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
204 |
|
|
.def<Eigen::VectorXd(BipedIG &, const Eigen::Vector3d &, |
205 |
|
|
const Eigen::Matrix3d &, const Eigen::Isometry3d &, |
206 |
|
|
const Eigen::Isometry3d &, const Eigen::VectorXd &, |
207 |
|
|
const double &, const int &)>( |
208 |
|
|
"solve", &solve, |
209 |
|
|
(bp::args("self", "com", "baseRotation", "leftFoot", "rightFoot", |
210 |
|
|
"q0"), |
211 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
212 |
|
|
.def<Eigen::VectorXd(BipedIG &, const pinocchio::SE3 &, |
213 |
|
|
const pinocchio::SE3 &, const pinocchio::SE3 &, |
214 |
|
|
const Eigen::VectorXd &)>( |
215 |
|
|
"solve", &solve, |
216 |
|
|
(bp::args("self", "base", "leftFoot", "rightFoot", "q0"))) |
217 |
|
|
.def<Eigen::VectorXd(BipedIG &, const Eigen::Isometry3d &, |
218 |
|
|
const Eigen::Isometry3d &, const Eigen::Isometry3d &, |
219 |
|
|
const Eigen::VectorXd &)>( |
220 |
|
|
"solve", &solve, |
221 |
|
|
(bp::args("self", "base", "leftFoot", "rightFoot", "q0"))) |
222 |
|
|
.def<bp::tuple(BipedIG &, const std::array<Eigen::Vector3d, 3> &, |
223 |
|
|
const std::array<pinocchio::SE3, 3> &, |
224 |
|
|
const std::array<pinocchio::SE3, 3> &, |
225 |
|
|
const Eigen::VectorXd &, const double &, const double &, |
226 |
|
|
const int &)>( |
227 |
|
|
"solve", &solve, |
228 |
|
|
(bp::args("self", "coms", "leftFeet", "rightFeet", "q0", "dt"), |
229 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
230 |
|
|
.def<bp::tuple(BipedIG &, const std::array<Eigen::Vector3d, 3> &, |
231 |
|
|
const std::array<Eigen::Isometry3d, 3> &, |
232 |
|
|
const std::array<Eigen::Isometry3d, 3> &, |
233 |
|
|
const Eigen::VectorXd &, const double &, const double &, |
234 |
|
|
const int &)>( |
235 |
|
|
"solve", &solve, |
236 |
|
|
(bp::args("self", "coms", "leftFeet", "rightFeet", "q0", "dt"), |
237 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
238 |
|
|
.def<bp::tuple(BipedIG &, const std::array<Eigen::Vector3d, 3> &, |
239 |
|
|
const std::array<Eigen::Matrix3d, 3> &, |
240 |
|
|
const std::array<pinocchio::SE3, 3> &, |
241 |
|
|
const std::array<pinocchio::SE3, 3> &, |
242 |
|
|
const Eigen::VectorXd &, const double &, const double &, |
243 |
|
|
const int &)>( |
244 |
|
|
"solve", &solve, |
245 |
|
|
(bp::args("self", "coms", |
246 |
|
|
"baseRotations" |
247 |
|
|
"leftFeet", |
248 |
|
|
"rightFeet", "q0", "dt"), |
249 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
250 |
|
|
.def<bp::tuple(BipedIG &, const std::array<Eigen::Vector3d, 3> &, |
251 |
|
|
const std::array<Eigen::Matrix3d, 3> &, |
252 |
|
|
const std::array<Eigen::Isometry3d, 3> &, |
253 |
|
|
const std::array<Eigen::Isometry3d, 3> &, |
254 |
|
|
const Eigen::VectorXd &, const double &, const double &, |
255 |
|
|
const int &)>( |
256 |
|
|
"solve", &solve, |
257 |
|
|
(bp::args("self", "coms", "baseRotations", "leftFeet", "rightFeet", |
258 |
|
|
"q0", "dt"), |
259 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 0)) |
260 |
|
|
.def<bp::tuple(BipedIG &, const bp::list &, const bp::list &, |
261 |
|
|
const bp::list &, const Eigen::VectorXd &, |
262 |
|
|
const double &)>( |
263 |
|
|
"solve", &solve, |
264 |
|
|
(bp::args("self", "bases", "leftFeet", "rightFeet", "q0", "dt"))) |
265 |
|
|
.def<bp::tuple(BipedIG &, const std::array<Eigen::Isometry3d, 3> &, |
266 |
|
|
const std::array<Eigen::Isometry3d, 3> &, |
267 |
|
|
const std::array<Eigen::Isometry3d, 3> &, |
268 |
|
|
const Eigen::VectorXd &, const double &)>( |
269 |
|
|
"solve", &solve, |
270 |
|
|
(bp::args("self", "bases", "leftFeet", "rightFeet", "q0", "dt"))) |
271 |
|
|
.def<void (BipedIG::*)(const Eigen::Vector3d &)>( |
272 |
|
|
"set_com_from_waist", &BipedIG::set_com_from_waist, |
273 |
|
|
bp::args("self", "com_from_waist")) |
274 |
|
|
.def<void (BipedIG::*)(const Eigen::VectorXd &)>( |
275 |
|
|
"set_com_from_waist", &BipedIG::set_com_from_waist, |
276 |
|
|
bp::args("self", "q")) |
277 |
|
|
.def("model", &BipedIG::get_model, |
278 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
279 |
|
|
bp::args("self")) |
280 |
|
|
.def("data", &BipedIG::get_data, |
281 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
282 |
|
|
bp::args("self")) |
283 |
|
|
.def<void (BipedIG::*)(const Eigen::Vector3d &, const pinocchio::SE3 &, |
284 |
|
|
const pinocchio::SE3 &, const Eigen::VectorXd &, |
285 |
|
|
const double &, const int &)>( |
286 |
|
|
"correctCoMfromWaist", &BipedIG::correctCoMfromWaist, |
287 |
|
|
(bp::args("self", "com", "leftFoot", "rightFoot", "q0"), |
288 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 20)) |
289 |
|
|
.def<void (BipedIG::*)(const Eigen::Vector3d &, const Eigen::Isometry3d &, |
290 |
|
|
const Eigen::Isometry3d &, const Eigen::VectorXd &, |
291 |
|
|
const double &, const int &)>( |
292 |
|
|
"correctCoMfromWaist", &BipedIG::correctCoMfromWaist, |
293 |
|
|
(bp::args("self", "com", "leftFoot", "rightFoot", "q0"), |
294 |
|
|
bp::arg("tolerance") = 1e-10, bp::arg("max_iterations") = 20)) |
295 |
|
|
.def("get_com_from_waist", &BipedIG::get_com_from_waist, |
296 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
297 |
|
|
bp::args("self")) |
298 |
|
|
.def("get_left_leg_settings", &BipedIG::get_left_leg_settings, |
299 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
300 |
|
|
bp::args("self")) |
301 |
|
|
.def("get_right_leg_settings", &BipedIG::get_right_leg_settings, |
302 |
|
|
bp::return_value_policy<bp::reference_existing_object>(), |
303 |
|
|
bp::args("self")); |
304 |
|
|
} |
305 |
|
|
} // namespace python |
306 |
|
|
} // namespace aig |