1 /*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33 #include <dart/dart.hpp>
34 #include <pybind11/pybind11.h>
35 #include "eigen_geometry_pybind.h"
36 #include "eigen_pybind.h"
37
38 namespace py = pybind11;
39
40 namespace dart {
41 namespace python {
42
ReferentialSkeleton(py::module & m)43 void ReferentialSkeleton(py::module& m)
44 {
45 ::py::class_<
46 dart::dynamics::ReferentialSkeleton,
47 dart::dynamics::MetaSkeleton,
48 std::shared_ptr<dart::dynamics::ReferentialSkeleton>>(
49 m, "ReferentialSkeleton")
50 .def(
51 "getLockableReference",
52 +[](const dart::dynamics::ReferentialSkeleton* self)
53 -> std::unique_ptr<dart::common::LockableReference> {
54 return self->getLockableReference();
55 })
56 .def(
57 "setName",
58 +[](dart::dynamics::ReferentialSkeleton* self,
59 const std::string& _name) -> const std::string& {
60 return self->setName(_name);
61 },
62 ::py::return_value_policy::reference_internal,
63 ::py::arg("name"))
64 .def(
65 "getName",
66 +[](const dart::dynamics::ReferentialSkeleton* self)
67 -> const std::string& { return self->getName(); },
68 ::py::return_value_policy::reference_internal)
69 .def(
70 "getNumSkeletons",
71 +[](const dart::dynamics::ReferentialSkeleton* self) -> std::size_t {
72 return self->getNumSkeletons();
73 })
74 .def(
75 "hasSkeleton",
76 +[](const dart::dynamics::ReferentialSkeleton* self,
77 const dart::dynamics::Skeleton* skel) -> bool {
78 return self->hasSkeleton(skel);
79 },
80 ::py::arg("skel"))
81 .def(
82 "getNumBodyNodes",
83 +[](const dart::dynamics::ReferentialSkeleton* self) -> std::size_t {
84 return self->getNumBodyNodes();
85 })
86 .def(
87 "getBodyNodes",
88 +[](dart::dynamics::ReferentialSkeleton* self)
89 -> const std::vector<dart::dynamics::BodyNode*>& {
90 return self->getBodyNodes();
91 })
92 .def(
93 "getBodyNodes",
94 +[](dart::dynamics::ReferentialSkeleton* self,
95 const std::string& name)
96 -> std::vector<dart::dynamics::BodyNode*> {
97 return self->getBodyNodes(name);
98 },
99 ::py::arg("name"))
100 .def(
101 "getBodyNodes",
102 +[](const dart::dynamics::ReferentialSkeleton* self,
103 const std::string& name)
104 -> std::vector<const dart::dynamics::BodyNode*> {
105 return self->getBodyNodes(name);
106 },
107 ::py::arg("name"))
108 .def(
109 "hasBodyNode",
110 +[](const dart::dynamics::ReferentialSkeleton* self,
111 const dart::dynamics::BodyNode* bodyNode) -> bool {
112 return self->hasBodyNode(bodyNode);
113 },
114 ::py::arg("bodyNode"))
115 .def(
116 "getIndexOf",
117 +[](const dart::dynamics::ReferentialSkeleton* self,
118 const dart::dynamics::BodyNode* _bn) -> std::size_t {
119 return self->getIndexOf(_bn);
120 },
121 ::py::arg("bn"))
122 .def(
123 "getIndexOf",
124 +[](const dart::dynamics::ReferentialSkeleton* self,
125 const dart::dynamics::BodyNode* _bn,
126 bool _warning) -> std::size_t {
127 return self->getIndexOf(_bn, _warning);
128 },
129 ::py::arg("bn"),
130 ::py::arg("warning"))
131 .def(
132 "getNumJoints",
133 +[](const dart::dynamics::ReferentialSkeleton* self) -> std::size_t {
134 return self->getNumJoints();
135 })
136 .def(
137 "getJoints",
138 +[](dart::dynamics::ReferentialSkeleton* self)
139 -> std::vector<dart::dynamics::Joint*> {
140 return self->getJoints();
141 })
142 .def(
143 "getJoints",
144 +[](const dart::dynamics::ReferentialSkeleton* self)
145 -> std::vector<const dart::dynamics::Joint*> {
146 return self->getJoints();
147 })
148 .def(
149 "getJoints",
150 +[](dart::dynamics::ReferentialSkeleton* self,
151 const std::string& name) -> std::vector<dart::dynamics::Joint*> {
152 return self->getJoints(name);
153 },
154 ::py::arg("name"))
155 .def(
156 "getJoints",
157 +[](const dart::dynamics::ReferentialSkeleton* self,
158 const std::string& name)
159 -> std::vector<const dart::dynamics::Joint*> {
160 return self->getJoints(name);
161 },
162 ::py::arg("name"))
163 .def(
164 "hasJoint",
165 +[](const dart::dynamics::ReferentialSkeleton* self,
166 const dart::dynamics::Joint* joint) -> bool {
167 return self->hasJoint(joint);
168 },
169 ::py::arg("joint"))
170 .def(
171 "getIndexOf",
172 +[](const dart::dynamics::ReferentialSkeleton* self,
173 const dart::dynamics::Joint* _joint) -> std::size_t {
174 return self->getIndexOf(_joint);
175 },
176 ::py::arg("joint"))
177 .def(
178 "getIndexOf",
179 +[](const dart::dynamics::ReferentialSkeleton* self,
180 const dart::dynamics::Joint* _joint,
181 bool _warning) -> std::size_t {
182 return self->getIndexOf(_joint, _warning);
183 },
184 ::py::arg("joint"),
185 ::py::arg("warning"))
186 .def(
187 "getNumDofs",
188 +[](const dart::dynamics::ReferentialSkeleton* self) -> std::size_t {
189 return self->getNumDofs();
190 })
191 .def(
192 "getDofs",
193 +[](const dart::dynamics::ReferentialSkeleton* self)
194 -> std::vector<const dart::dynamics::DegreeOfFreedom*> {
195 return self->getDofs();
196 })
197 .def(
198 "getIndexOf",
199 +[](const dart::dynamics::ReferentialSkeleton* self,
200 const dart::dynamics::DegreeOfFreedom* _dof) -> std::size_t {
201 return self->getIndexOf(_dof);
202 },
203 ::py::arg("dof"))
204 .def(
205 "getIndexOf",
206 +[](const dart::dynamics::ReferentialSkeleton* self,
207 const dart::dynamics::DegreeOfFreedom* _dof,
208 bool _warning) -> std::size_t {
209 return self->getIndexOf(_dof, _warning);
210 },
211 ::py::arg("dof"),
212 ::py::arg("warning"))
213 .def(
214 "getJacobian",
215 +[](const dart::dynamics::ReferentialSkeleton* self,
216 const dart::dynamics::JacobianNode* _node)
217 -> dart::math::Jacobian { return self->getJacobian(_node); },
218 ::py::arg("node"))
219 .def(
220 "getJacobian",
221 +[](const dart::dynamics::ReferentialSkeleton* self,
222 const dart::dynamics::JacobianNode* _node,
223 const dart::dynamics::Frame* _inCoordinatesOf)
224 -> dart::math::Jacobian {
225 return self->getJacobian(_node, _inCoordinatesOf);
226 },
227 ::py::arg("node"),
228 ::py::arg("inCoordinatesOf"))
229 .def(
230 "getJacobian",
231 +[](const dart::dynamics::ReferentialSkeleton* self,
232 const dart::dynamics::JacobianNode* _node,
233 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
234 return self->getJacobian(_node, _localOffset);
235 },
236 ::py::arg("node"),
237 ::py::arg("localOffset"))
238 .def(
239 "getJacobian",
240 +[](const dart::dynamics::ReferentialSkeleton* self,
241 const dart::dynamics::JacobianNode* _node,
242 const Eigen::Vector3d& _localOffset,
243 const dart::dynamics::Frame* _inCoordinatesOf)
244 -> dart::math::Jacobian {
245 return self->getJacobian(_node, _localOffset, _inCoordinatesOf);
246 },
247 ::py::arg("node"),
248 ::py::arg("localOffset"),
249 ::py::arg("inCoordinatesOf"))
250 .def(
251 "getWorldJacobian",
252 +[](const dart::dynamics::ReferentialSkeleton* self,
253 const dart::dynamics::JacobianNode* _node)
254 -> dart::math::Jacobian { return self->getWorldJacobian(_node); },
255 ::py::arg("node"))
256 .def(
257 "getWorldJacobian",
258 +[](const dart::dynamics::ReferentialSkeleton* self,
259 const dart::dynamics::JacobianNode* _node,
260 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
261 return self->getWorldJacobian(_node, _localOffset);
262 },
263 ::py::arg("node"),
264 ::py::arg("localOffset"))
265 .def(
266 "getLinearJacobian",
267 +[](const dart::dynamics::ReferentialSkeleton* self,
268 const dart::dynamics::JacobianNode* _node)
269 -> dart::math::LinearJacobian {
270 return self->getLinearJacobian(_node);
271 },
272 ::py::arg("node"))
273 .def(
274 "getLinearJacobian",
275 +[](const dart::dynamics::ReferentialSkeleton* self,
276 const dart::dynamics::JacobianNode* _node,
277 const dart::dynamics::Frame* _inCoordinatesOf)
278 -> dart::math::LinearJacobian {
279 return self->getLinearJacobian(_node, _inCoordinatesOf);
280 },
281 ::py::arg("node"),
282 ::py::arg("inCoordinatesOf"))
283 .def(
284 "getLinearJacobian",
285 +[](const dart::dynamics::ReferentialSkeleton* self,
286 const dart::dynamics::JacobianNode* _node,
287 const Eigen::Vector3d& _localOffset)
288 -> dart::math::LinearJacobian {
289 return self->getLinearJacobian(_node, _localOffset);
290 },
291 ::py::arg("node"),
292 ::py::arg("localOffset"))
293 .def(
294 "getLinearJacobian",
295 +[](const dart::dynamics::ReferentialSkeleton* self,
296 const dart::dynamics::JacobianNode* _node,
297 const Eigen::Vector3d& _localOffset,
298 const dart::dynamics::Frame* _inCoordinatesOf)
299 -> dart::math::LinearJacobian {
300 return self->getLinearJacobian(
301 _node, _localOffset, _inCoordinatesOf);
302 },
303 ::py::arg("node"),
304 ::py::arg("localOffset"),
305 ::py::arg("inCoordinatesOf"))
306 .def(
307 "getAngularJacobian",
308 +[](const dart::dynamics::ReferentialSkeleton* self,
309 const dart::dynamics::JacobianNode* _node)
310 -> dart::math::AngularJacobian {
311 return self->getAngularJacobian(_node);
312 },
313 ::py::arg("node"))
314 .def(
315 "getAngularJacobian",
316 +[](const dart::dynamics::ReferentialSkeleton* self,
317 const dart::dynamics::JacobianNode* _node,
318 const dart::dynamics::Frame* _inCoordinatesOf)
319 -> dart::math::AngularJacobian {
320 return self->getAngularJacobian(_node, _inCoordinatesOf);
321 },
322 ::py::arg("node"),
323 ::py::arg("inCoordinatesOf"))
324 .def(
325 "getJacobianSpatialDeriv",
326 +[](const dart::dynamics::ReferentialSkeleton* self,
327 const dart::dynamics::JacobianNode* _node)
328 -> dart::math::Jacobian {
329 return self->getJacobianSpatialDeriv(_node);
330 },
331 ::py::arg("node"))
332 .def(
333 "getJacobianSpatialDeriv",
334 +[](const dart::dynamics::ReferentialSkeleton* self,
335 const dart::dynamics::JacobianNode* _node,
336 const dart::dynamics::Frame* _inCoordinatesOf)
337 -> dart::math::Jacobian {
338 return self->getJacobianSpatialDeriv(_node, _inCoordinatesOf);
339 },
340 ::py::arg("node"),
341 ::py::arg("inCoordinatesOf"))
342 .def(
343 "getJacobianSpatialDeriv",
344 +[](const dart::dynamics::ReferentialSkeleton* self,
345 const dart::dynamics::JacobianNode* _node,
346 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
347 return self->getJacobianSpatialDeriv(_node, _localOffset);
348 },
349 ::py::arg("node"),
350 ::py::arg("localOffset"))
351 .def(
352 "getJacobianSpatialDeriv",
353 +[](const dart::dynamics::ReferentialSkeleton* self,
354 const dart::dynamics::JacobianNode* _node,
355 const Eigen::Vector3d& _localOffset,
356 const dart::dynamics::Frame* _inCoordinatesOf)
357 -> dart::math::Jacobian {
358 return self->getJacobianSpatialDeriv(
359 _node, _localOffset, _inCoordinatesOf);
360 },
361 ::py::arg("node"),
362 ::py::arg("localOffset"),
363 ::py::arg("inCoordinatesOf"))
364 .def(
365 "getJacobianClassicDeriv",
366 +[](const dart::dynamics::ReferentialSkeleton* self,
367 const dart::dynamics::JacobianNode* _node)
368 -> dart::math::Jacobian {
369 return self->getJacobianClassicDeriv(_node);
370 },
371 ::py::arg("node"))
372 .def(
373 "getJacobianClassicDeriv",
374 +[](const dart::dynamics::ReferentialSkeleton* self,
375 const dart::dynamics::JacobianNode* _node,
376 const dart::dynamics::Frame* _inCoordinatesOf)
377 -> dart::math::Jacobian {
378 return self->getJacobianClassicDeriv(_node, _inCoordinatesOf);
379 },
380 ::py::arg("node"),
381 ::py::arg("inCoordinatesOf"))
382 .def(
383 "getJacobianClassicDeriv",
384 +[](const dart::dynamics::ReferentialSkeleton* self,
385 const dart::dynamics::JacobianNode* _node,
386 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
387 return self->getJacobianClassicDeriv(_node, _localOffset);
388 },
389 ::py::arg("node"),
390 ::py::arg("localOffset"))
391 .def(
392 "getJacobianClassicDeriv",
393 +[](const dart::dynamics::ReferentialSkeleton* self,
394 const dart::dynamics::JacobianNode* _node,
395 const Eigen::Vector3d& _localOffset,
396 const dart::dynamics::Frame* _inCoordinatesOf)
397 -> dart::math::Jacobian {
398 return self->getJacobianClassicDeriv(
399 _node, _localOffset, _inCoordinatesOf);
400 },
401 ::py::arg("node"),
402 ::py::arg("localOffset"),
403 ::py::arg("inCoordinatesOf"))
404 .def(
405 "getLinearJacobianDeriv",
406 +[](const dart::dynamics::ReferentialSkeleton* self,
407 const dart::dynamics::JacobianNode* _node)
408 -> dart::math::LinearJacobian {
409 return self->getLinearJacobianDeriv(_node);
410 },
411 ::py::arg("node"))
412 .def(
413 "getLinearJacobianDeriv",
414 +[](const dart::dynamics::ReferentialSkeleton* self,
415 const dart::dynamics::JacobianNode* _node,
416 const dart::dynamics::Frame* _inCoordinatesOf)
417 -> dart::math::LinearJacobian {
418 return self->getLinearJacobianDeriv(_node, _inCoordinatesOf);
419 },
420 ::py::arg("node"),
421 ::py::arg("inCoordinatesOf"))
422 .def(
423 "getLinearJacobianDeriv",
424 +[](const dart::dynamics::ReferentialSkeleton* self,
425 const dart::dynamics::JacobianNode* _node,
426 const Eigen::Vector3d& _localOffset)
427 -> dart::math::LinearJacobian {
428 return self->getLinearJacobianDeriv(_node, _localOffset);
429 },
430 ::py::arg("node"),
431 ::py::arg("localOffset"))
432 .def(
433 "getLinearJacobianDeriv",
434 +[](const dart::dynamics::ReferentialSkeleton* self,
435 const dart::dynamics::JacobianNode* _node,
436 const Eigen::Vector3d& _localOffset,
437 const dart::dynamics::Frame* _inCoordinatesOf)
438 -> dart::math::LinearJacobian {
439 return self->getLinearJacobianDeriv(
440 _node, _localOffset, _inCoordinatesOf);
441 },
442 ::py::arg("node"),
443 ::py::arg("localOffset"),
444 ::py::arg("inCoordinatesOf"))
445 .def(
446 "getAngularJacobianDeriv",
447 +[](const dart::dynamics::ReferentialSkeleton* self,
448 const dart::dynamics::JacobianNode* _node)
449 -> dart::math::AngularJacobian {
450 return self->getAngularJacobianDeriv(_node);
451 },
452 ::py::arg("node"))
453 .def(
454 "getAngularJacobianDeriv",
455 +[](const dart::dynamics::ReferentialSkeleton* self,
456 const dart::dynamics::JacobianNode* _node,
457 const dart::dynamics::Frame* _inCoordinatesOf)
458 -> dart::math::AngularJacobian {
459 return self->getAngularJacobianDeriv(_node, _inCoordinatesOf);
460 },
461 ::py::arg("node"),
462 ::py::arg("inCoordinatesOf"))
463 .def(
464 "getMass",
465 +[](const dart::dynamics::ReferentialSkeleton* self) -> double {
466 return self->getMass();
467 })
468 .def(
469 "clearExternalForces",
470 +[](dart::dynamics::ReferentialSkeleton* self) {
471 self->clearExternalForces();
472 })
473 .def(
474 "clearInternalForces",
475 +[](dart::dynamics::ReferentialSkeleton* self) {
476 self->clearInternalForces();
477 })
478 .def(
479 "computeKineticEnergy",
480 +[](const dart::dynamics::ReferentialSkeleton* self) -> double {
481 return self->computeKineticEnergy();
482 })
483 .def(
484 "computePotentialEnergy",
485 +[](const dart::dynamics::ReferentialSkeleton* self) -> double {
486 return self->computePotentialEnergy();
487 })
488 // .def(
489 // "clearCollidingBodies",
490 // +[](dart::dynamics::ReferentialSkeleton* self) {
491 // self->clearCollidingBodies();
492 // })
493 .def(
494 "getCOM",
495 +[](const dart::dynamics::ReferentialSkeleton* self)
496 -> Eigen::Vector3d { return self->getCOM(); })
497 .def(
498 "getCOM",
499 +[](const dart::dynamics::ReferentialSkeleton* self,
500 const dart::dynamics::Frame* _withRespectTo) -> Eigen::Vector3d {
501 return self->getCOM(_withRespectTo);
502 },
503 ::py::arg("withRespectTo"))
504 .def(
505 "getCOMSpatialVelocity",
506 +[](const dart::dynamics::ReferentialSkeleton* self)
507 -> Eigen::Vector6d { return self->getCOMSpatialVelocity(); })
508 .def(
509 "getCOMSpatialVelocity",
510 +[](const dart::dynamics::ReferentialSkeleton* self,
511 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector6d {
512 return self->getCOMSpatialVelocity(_relativeTo);
513 },
514 ::py::arg("relativeTo"))
515 .def(
516 "getCOMSpatialVelocity",
517 +[](const dart::dynamics::ReferentialSkeleton* self,
518 const dart::dynamics::Frame* _relativeTo,
519 const dart::dynamics::Frame* _inCoordinatesOf)
520 -> Eigen::Vector6d {
521 return self->getCOMSpatialVelocity(_relativeTo, _inCoordinatesOf);
522 },
523 ::py::arg("relativeTo"),
524 ::py::arg("inCoordinatesOf"))
525 .def(
526 "getCOMLinearVelocity",
527 +[](const dart::dynamics::ReferentialSkeleton* self)
528 -> Eigen::Vector3d { return self->getCOMLinearVelocity(); })
529 .def(
530 "getCOMLinearVelocity",
531 +[](const dart::dynamics::ReferentialSkeleton* self,
532 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector3d {
533 return self->getCOMLinearVelocity(_relativeTo);
534 },
535 ::py::arg("relativeTo"))
536 .def(
537 "getCOMLinearVelocity",
538 +[](const dart::dynamics::ReferentialSkeleton* self,
539 const dart::dynamics::Frame* _relativeTo,
540 const dart::dynamics::Frame* _inCoordinatesOf)
541 -> Eigen::Vector3d {
542 return self->getCOMLinearVelocity(_relativeTo, _inCoordinatesOf);
543 },
544 ::py::arg("relativeTo"),
545 ::py::arg("inCoordinatesOf"))
546 .def(
547 "getCOMSpatialAcceleration",
548 +[](const dart::dynamics::ReferentialSkeleton* self)
549 -> Eigen::Vector6d { return self->getCOMSpatialAcceleration(); })
550 .def(
551 "getCOMSpatialAcceleration",
552 +[](const dart::dynamics::ReferentialSkeleton* self,
553 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector6d {
554 return self->getCOMSpatialAcceleration(_relativeTo);
555 },
556 ::py::arg("relativeTo"))
557 .def(
558 "getCOMSpatialAcceleration",
559 +[](const dart::dynamics::ReferentialSkeleton* self,
560 const dart::dynamics::Frame* _relativeTo,
561 const dart::dynamics::Frame* _inCoordinatesOf)
562 -> Eigen::Vector6d {
563 return self->getCOMSpatialAcceleration(
564 _relativeTo, _inCoordinatesOf);
565 },
566 ::py::arg("relativeTo"),
567 ::py::arg("inCoordinatesOf"))
568 .def(
569 "getCOMLinearAcceleration",
570 +[](const dart::dynamics::ReferentialSkeleton* self)
571 -> Eigen::Vector3d { return self->getCOMLinearAcceleration(); })
572 .def(
573 "getCOMLinearAcceleration",
574 +[](const dart::dynamics::ReferentialSkeleton* self,
575 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector3d {
576 return self->getCOMLinearAcceleration(_relativeTo);
577 },
578 ::py::arg("relativeTo"))
579 .def(
580 "getCOMLinearAcceleration",
581 +[](const dart::dynamics::ReferentialSkeleton* self,
582 const dart::dynamics::Frame* _relativeTo,
583 const dart::dynamics::Frame* _inCoordinatesOf)
584 -> Eigen::Vector3d {
585 return self->getCOMLinearAcceleration(
586 _relativeTo, _inCoordinatesOf);
587 },
588 ::py::arg("relativeTo"),
589 ::py::arg("inCoordinatesOf"))
590 .def(
591 "getCOMJacobian",
592 +[](const dart::dynamics::ReferentialSkeleton* self)
593 -> dart::math::Jacobian { return self->getCOMJacobian(); })
594 .def(
595 "getCOMJacobian",
596 +[](const dart::dynamics::ReferentialSkeleton* self,
597 const dart::dynamics::Frame* _inCoordinatesOf)
598 -> dart::math::Jacobian {
599 return self->getCOMJacobian(_inCoordinatesOf);
600 },
601 ::py::arg("inCoordinatesOf"))
602 .def(
603 "getCOMLinearJacobian",
604 +[](const dart::dynamics::ReferentialSkeleton* self)
605 -> dart::math::LinearJacobian {
606 return self->getCOMLinearJacobian();
607 })
608 .def(
609 "getCOMLinearJacobian",
610 +[](const dart::dynamics::ReferentialSkeleton* self,
611 const dart::dynamics::Frame* _inCoordinatesOf)
612 -> dart::math::LinearJacobian {
613 return self->getCOMLinearJacobian(_inCoordinatesOf);
614 },
615 ::py::arg("inCoordinatesOf"))
616 .def(
617 "getCOMJacobianSpatialDeriv",
618 +[](const dart::dynamics::ReferentialSkeleton* self)
619 -> dart::math::Jacobian {
620 return self->getCOMJacobianSpatialDeriv();
621 })
622 .def(
623 "getCOMJacobianSpatialDeriv",
624 +[](const dart::dynamics::ReferentialSkeleton* self,
625 const dart::dynamics::Frame* _inCoordinatesOf)
626 -> dart::math::Jacobian {
627 return self->getCOMJacobianSpatialDeriv(_inCoordinatesOf);
628 },
629 ::py::arg("inCoordinatesOf"))
630 .def(
631 "getCOMLinearJacobianDeriv",
632 +[](const dart::dynamics::ReferentialSkeleton* self)
633 -> dart::math::LinearJacobian {
634 return self->getCOMLinearJacobianDeriv();
635 })
636 .def(
637 "getCOMLinearJacobianDeriv",
638 +[](const dart::dynamics::ReferentialSkeleton* self,
639 const dart::dynamics::Frame* _inCoordinatesOf)
640 -> dart::math::LinearJacobian {
641 return self->getCOMLinearJacobianDeriv(_inCoordinatesOf);
642 },
643 ::py::arg("inCoordinatesOf"));
644 }
645
646 } // namespace python
647 } // namespace dart
648