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 <pybind11/stl.h>
36 #include "eigen_geometry_pybind.h"
37 #include "eigen_pybind.h"
38
39 namespace py = pybind11;
40
41 #define DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(joint_type) \
42 .def( \
43 "create" #joint_type "AndBodyNodePair", \
44 +[](dart::dynamics::Skeleton* self) \
45 -> std:: \
46 pair<dart::dynamics::joint_type*, dart::dynamics::BodyNode*> { \
47 return self->createJointAndBodyNodePair< \
48 dart::dynamics::joint_type, \
49 dart::dynamics::BodyNode>(); \
50 }, \
51 ::py::return_value_policy::reference_internal) \
52 .def( \
53 "create" #joint_type "AndBodyNodePair", \
54 +[](dart::dynamics::Skeleton* self, \
55 dart::dynamics::BodyNode* parent) \
56 -> std::pair< \
57 dart::dynamics::joint_type*, \
58 dart::dynamics::BodyNode*> { \
59 return self->createJointAndBodyNodePair< \
60 dart::dynamics::joint_type, \
61 dart::dynamics::BodyNode>(parent); \
62 }, \
63 ::py::return_value_policy::reference_internal, \
64 ::py::arg("parent")) \
65 .def( \
66 "create" #joint_type "AndBodyNodePair", \
67 +[](dart::dynamics::Skeleton* self, \
68 dart::dynamics::BodyNode* parent, \
69 const dart::dynamics::joint_type::Properties& jointProperties) \
70 -> std::pair< \
71 dart::dynamics::joint_type*, \
72 dart::dynamics::BodyNode*> { \
73 return self->createJointAndBodyNodePair< \
74 dart::dynamics::joint_type, \
75 dart::dynamics::BodyNode>(parent, jointProperties); \
76 }, \
77 ::py::return_value_policy::reference_internal, \
78 ::py::arg("parent"), \
79 ::py::arg("jointProperties")) \
80 .def( \
81 "create" #joint_type "AndBodyNodePair", \
82 +[](dart::dynamics::Skeleton* self, \
83 dart::dynamics::BodyNode* parent, \
84 const dart::dynamics::joint_type::Properties& jointProperties, \
85 const dart::dynamics::BodyNode::Properties& bodyProperties) \
86 -> std::pair< \
87 dart::dynamics::joint_type*, \
88 dart::dynamics::BodyNode*> { \
89 return self->createJointAndBodyNodePair< \
90 dart::dynamics::joint_type, \
91 dart::dynamics::BodyNode>( \
92 parent, jointProperties, bodyProperties); \
93 }, \
94 ::py::return_value_policy::reference_internal, \
95 ::py::arg("parent").none(true), \
96 ::py::arg("jointProperties"), \
97 ::py::arg("bodyProperties"))
98
99 namespace dart {
100 namespace python {
101
Skeleton(py::module & m)102 void Skeleton(py::module& m)
103 {
104 ::py::class_<
105 dart::dynamics::Skeleton,
106 dart::dynamics::MetaSkeleton,
107 std::shared_ptr<dart::dynamics::Skeleton>>(m, "Skeleton")
108 .def(::py::init(+[]() -> dart::dynamics::SkeletonPtr {
109 return dart::dynamics::Skeleton::create();
110 }))
111 .def(
112 ::py::init(
113 +[](const std::string& _name) -> dart::dynamics::SkeletonPtr {
114 return dart::dynamics::Skeleton::create(_name);
115 }),
116 ::py::arg("name"))
117 .def(
118 ::py::init(
119 +[](const dart::dynamics::Skeleton::AspectPropertiesData&
120 properties) -> dart::dynamics::SkeletonPtr {
121 return dart::dynamics::Skeleton::create(properties);
122 }),
123 ::py::arg("properties"))
124 .def(
125 "getPtr",
126 +[](dart::dynamics::Skeleton* self) -> dart::dynamics::SkeletonPtr {
127 return self->getPtr();
128 })
129 .def(
130 "getPtr",
131 +[](const dart::dynamics::Skeleton* self)
132 -> dart::dynamics::ConstSkeletonPtr { return self->getPtr(); })
133 .def(
134 "getSkeleton",
135 +[](dart::dynamics::Skeleton* self) -> dart::dynamics::SkeletonPtr {
136 return self->getSkeleton();
137 })
138 .def(
139 "getSkeleton",
140 +[](const dart::dynamics::Skeleton* self)
141 -> dart::dynamics::ConstSkeletonPtr {
142 return self->getSkeleton();
143 })
144 .def(
145 "getLockableReference",
146 +[](const dart::dynamics::Skeleton* self)
147 -> std::unique_ptr<dart::common::LockableReference> {
148 return self->getLockableReference();
149 })
150 .def(
151 "clone",
152 +[](const dart::dynamics::Skeleton* self)
153 -> dart::dynamics::SkeletonPtr { return self->cloneSkeleton(); })
154 .def(
155 "clone",
156 +[](const dart::dynamics::Skeleton* self,
157 const std::string& cloneName) -> dart::dynamics::SkeletonPtr {
158 return self->cloneSkeleton(cloneName);
159 },
160 ::py::arg("cloneName"))
161 .def(
162 "setConfiguration",
163 +[](dart::dynamics::Skeleton* self,
164 const dart::dynamics::Skeleton::Configuration& configuration)
165 -> void { return self->setConfiguration(configuration); },
166 ::py::arg("configuration"))
167 .def(
168 "getConfiguration",
169 +[](const dart::dynamics::Skeleton* self)
170 -> dart::dynamics::Skeleton::Configuration {
171 return self->getConfiguration();
172 })
173 .def(
174 "getConfiguration",
175 +[](const dart::dynamics::Skeleton* self,
176 int flags) -> dart::dynamics::Skeleton::Configuration {
177 return self->getConfiguration(flags);
178 },
179 ::py::arg("flags"))
180 .def(
181 "getConfiguration",
182 +[](const dart::dynamics::Skeleton* self,
183 const std::vector<std::size_t>& indices)
184 -> dart::dynamics::Skeleton::Configuration {
185 return self->getConfiguration(indices);
186 },
187 ::py::arg("indices"))
188 .def(
189 "getConfiguration",
190 +[](const dart::dynamics::Skeleton* self,
191 const std::vector<std::size_t>& indices,
192 int flags) -> dart::dynamics::Skeleton::Configuration {
193 return self->getConfiguration(indices, flags);
194 },
195 ::py::arg("indices"),
196 ::py::arg("flags"))
197 .def(
198 "setState",
199 +[](dart::dynamics::Skeleton* self,
200 const dart::dynamics::Skeleton::State& state) -> void {
201 return self->setState(state);
202 },
203 ::py::arg("state"))
204 .def(
205 "getState",
206 +[](const dart::dynamics::Skeleton* self)
207 -> dart::dynamics::Skeleton::State { return self->getState(); })
208 .def(
209 "setProperties",
210 +[](dart::dynamics::Skeleton* self,
211 const dart::dynamics::Skeleton::Properties& properties) -> void {
212 return self->setProperties(properties);
213 },
214 ::py::arg("properties"))
215 .def(
216 "getProperties",
217 +[](const dart::dynamics::Skeleton* self)
218 -> dart::dynamics::Skeleton::Properties {
219 return self->getProperties();
220 })
221 .def(
222 "setProperties",
223 +[](dart::dynamics::Skeleton* self,
224 const dart::dynamics::Skeleton::AspectProperties& properties)
225 -> void { return self->setProperties(properties); },
226 ::py::arg("properties"))
227 .def(
228 "setAspectProperties",
229 +[](dart::dynamics::Skeleton* self,
230 const dart::dynamics::Skeleton::AspectProperties& properties)
231 -> void { return self->setAspectProperties(properties); },
232 ::py::arg("properties"))
233 .def(
234 "setName",
235 +[](dart::dynamics::Skeleton* self, const std::string& _name)
236 -> const std::string& { return self->setName(_name); },
237 ::py::return_value_policy::reference_internal,
238 ::py::arg("name"))
239 .def(
240 "getName",
241 +[](const dart::dynamics::Skeleton* self) -> const std::string& {
242 return self->getName();
243 },
244 ::py::return_value_policy::reference_internal)
245 .def(
246 "setSelfCollisionCheck",
247 +[](dart::dynamics::Skeleton* self, bool enable) -> void {
248 return self->setSelfCollisionCheck(enable);
249 },
250 ::py::arg("enable"))
251 .def(
252 "getSelfCollisionCheck",
253 +[](const dart::dynamics::Skeleton* self) -> bool {
254 return self->getSelfCollisionCheck();
255 })
256 .def(
257 "enableSelfCollisionCheck",
258 +[](dart::dynamics::Skeleton* self) -> void {
259 return self->enableSelfCollisionCheck();
260 })
261 .def(
262 "disableSelfCollisionCheck",
263 +[](dart::dynamics::Skeleton* self) -> void {
264 return self->disableSelfCollisionCheck();
265 })
266 .def(
267 "isEnabledSelfCollisionCheck",
268 +[](const dart::dynamics::Skeleton* self) -> bool {
269 return self->isEnabledSelfCollisionCheck();
270 })
271 .def(
272 "setAdjacentBodyCheck",
273 +[](dart::dynamics::Skeleton* self, bool enable) -> void {
274 return self->setAdjacentBodyCheck(enable);
275 },
276 ::py::arg("enable"))
277 .def(
278 "getAdjacentBodyCheck",
279 +[](const dart::dynamics::Skeleton* self) -> bool {
280 return self->getAdjacentBodyCheck();
281 })
282 .def(
283 "enableAdjacentBodyCheck",
284 +[](dart::dynamics::Skeleton* self) -> void {
285 return self->enableAdjacentBodyCheck();
286 })
287 .def(
288 "disableAdjacentBodyCheck",
289 +[](dart::dynamics::Skeleton* self) -> void {
290 return self->disableAdjacentBodyCheck();
291 })
292 .def(
293 "isEnabledAdjacentBodyCheck",
294 +[](const dart::dynamics::Skeleton* self) -> bool {
295 return self->isEnabledAdjacentBodyCheck();
296 })
297 .def(
298 "setMobile",
299 +[](dart::dynamics::Skeleton* self, bool _isMobile) -> void {
300 return self->setMobile(_isMobile);
301 },
302 ::py::arg("isMobile"))
303 .def(
304 "isMobile",
305 +[](const dart::dynamics::Skeleton* self) -> bool {
306 return self->isMobile();
307 })
308 .def(
309 "setTimeStep",
310 +[](dart::dynamics::Skeleton* self, double _timeStep) -> void {
311 return self->setTimeStep(_timeStep);
312 },
313 ::py::arg("timeStep"))
314 .def(
315 "getTimeStep",
316 +[](const dart::dynamics::Skeleton* self) -> double {
317 return self->getTimeStep();
318 })
319 .def(
320 "setGravity",
321 +[](dart::dynamics::Skeleton* self, const Eigen::Vector3d& _gravity)
322 -> void { return self->setGravity(_gravity); },
323 ::py::arg("gravity"))
324 .def(
325 "getGravity",
326 +[](const dart::dynamics::Skeleton* self) -> const Eigen::Vector3d& {
327 return self->getGravity();
328 },
329 ::py::return_value_policy::reference_internal)
330 // clang-format off
331 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(WeldJoint)
332 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(RevoluteJoint)
333 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(PrismaticJoint)
334 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(ScrewJoint)
335 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(UniversalJoint)
336 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(TranslationalJoint2D)
337 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(PlanarJoint)
338 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(EulerJoint)
339 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(BallJoint)
340 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(TranslationalJoint)
341 DARTPY_DEFINE_CREATE_JOINT_AND_BODY_NODE_PAIR(FreeJoint)
342 // clang-format on
343 .def(
344 "getNumBodyNodes",
345 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
346 return self->getNumBodyNodes();
347 })
348 .def(
349 "getNumRigidBodyNodes",
350 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
351 return self->getNumRigidBodyNodes();
352 })
353 .def(
354 "getNumSoftBodyNodes",
355 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
356 return self->getNumSoftBodyNodes();
357 })
358 .def(
359 "getNumTrees",
360 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
361 return self->getNumTrees();
362 })
363 .def(
364 "getRootBodyNode",
365 +[](dart::dynamics::Skeleton* self) -> dart::dynamics::BodyNode* {
366 return self->getRootBodyNode();
367 },
368 py::return_value_policy::reference)
369 .def(
370 "getRootBodyNode",
371 +[](dart::dynamics::Skeleton* self,
372 std::size_t index) -> dart::dynamics::BodyNode* {
373 return self->getRootBodyNode(index);
374 },
375 ::py::arg("treeIndex"),
376 py::return_value_policy::reference)
377 .def(
378 "getRootJoint",
379 +[](dart::dynamics::Skeleton* self) -> dart::dynamics::Joint* {
380 return self->getRootJoint();
381 },
382 py::return_value_policy::reference_internal)
383 .def(
384 "getRootJoint",
385 +[](dart::dynamics::Skeleton* self, std::size_t index)
386 -> dart::dynamics::Joint* { return self->getRootJoint(index); },
387 ::py::arg("treeIndex"),
388 py::return_value_policy::reference_internal)
389 .def(
390 "getBodyNodes",
391 +[](dart::dynamics::Skeleton* self)
392 -> const std::vector<dart::dynamics::BodyNode*>& {
393 return self->getBodyNodes();
394 })
395 .def(
396 "getBodyNodes",
397 +[](dart::dynamics::Skeleton* self, const std::string& name)
398 -> std::vector<dart::dynamics::BodyNode*> {
399 return self->getBodyNodes(name);
400 },
401 ::py::arg("name"))
402 .def(
403 "getBodyNodes",
404 +[](const dart::dynamics::Skeleton* self, const std::string& name)
405 -> std::vector<const dart::dynamics::BodyNode*> {
406 return self->getBodyNodes(name);
407 },
408 ::py::arg("name"))
409 .def(
410 "hasBodyNode",
411 +[](const dart::dynamics::Skeleton* self,
412 const dart::dynamics::BodyNode* bodyNode) -> bool {
413 return self->hasBodyNode(bodyNode);
414 },
415 ::py::arg("bodyNode"))
416 .def(
417 "getIndexOf",
418 +[](const dart::dynamics::Skeleton* self,
419 const dart::dynamics::BodyNode* _bn) -> std::size_t {
420 return self->getIndexOf(_bn);
421 },
422 ::py::arg("bn"))
423 .def(
424 "getIndexOf",
425 +[](const dart::dynamics::Skeleton* self,
426 const dart::dynamics::BodyNode* _bn,
427 bool _warning) -> std::size_t {
428 return self->getIndexOf(_bn, _warning);
429 },
430 ::py::arg("bn"),
431 ::py::arg("warning"))
432 .def(
433 "getTreeBodyNodes",
434 +[](const dart::dynamics::Skeleton* self, std::size_t _treeIdx)
435 -> std::vector<const dart::dynamics::BodyNode*> {
436 return self->getTreeBodyNodes(_treeIdx);
437 },
438 ::py::arg("treeIdx"))
439 .def(
440 "getNumJoints",
441 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
442 return self->getNumJoints();
443 })
444 .def(
445 "getJoint",
446 +[](dart::dynamics::Skeleton* self, std::size_t _idx)
447 -> dart::dynamics::Joint* { return self->getJoint(_idx); },
448 ::py::arg("idx"),
449 py::return_value_policy::reference_internal)
450 .def(
451 "getJoint",
452 +[](dart::dynamics::Skeleton* self, const std::string& name)
453 -> dart::dynamics::Joint* { return self->getJoint(name); },
454 ::py::arg("name"),
455 py::return_value_policy::reference_internal)
456 .def(
457 "getJoints",
458 +[](dart::dynamics::Skeleton* self)
459 -> std::vector<dart::dynamics::Joint*> {
460 return self->getJoints();
461 })
462 .def(
463 "getJoints",
464 +[](const dart::dynamics::Skeleton* self)
465 -> std::vector<const dart::dynamics::Joint*> {
466 return self->getJoints();
467 })
468 .def(
469 "getJoints",
470 +[](dart::dynamics::Skeleton* self,
471 const std::string& name) -> std::vector<dart::dynamics::Joint*> {
472 return self->getJoints(name);
473 },
474 ::py::arg("name"))
475 .def(
476 "getJoints",
477 +[](const dart::dynamics::Skeleton* self, const std::string& name)
478 -> std::vector<const dart::dynamics::Joint*> {
479 return self->getJoints(name);
480 },
481 ::py::arg("name"))
482 .def(
483 "hasJoint",
484 +[](const dart::dynamics::Skeleton* self,
485 const dart::dynamics::Joint* joint) -> bool {
486 return self->hasJoint(joint);
487 },
488 ::py::arg("joint"))
489 .def(
490 "getIndexOf",
491 +[](const dart::dynamics::Skeleton* self,
492 const dart::dynamics::Joint* _joint) -> std::size_t {
493 return self->getIndexOf(_joint);
494 },
495 ::py::arg("joint"))
496 .def(
497 "getIndexOf",
498 +[](const dart::dynamics::Skeleton* self,
499 const dart::dynamics::Joint* _joint,
500 bool _warning) -> std::size_t {
501 return self->getIndexOf(_joint, _warning);
502 },
503 ::py::arg("joint"),
504 ::py::arg("warning"))
505 .def(
506 "getNumDofs",
507 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
508 return self->getNumDofs();
509 })
510 .def(
511 "getDof",
512 +[](dart::dynamics::Skeleton* self,
513 std::size_t index) -> dart::dynamics::DegreeOfFreedom* {
514 return self->getDof(index);
515 },
516 ::py::return_value_policy::reference_internal,
517 ::py::arg("index"))
518 .def(
519 "getDof",
520 +[](dart::dynamics::Skeleton* self,
521 const std::string& name) -> dart::dynamics::DegreeOfFreedom* {
522 return self->getDof(name);
523 },
524 ::py::return_value_policy::reference_internal,
525 ::py::arg("name"))
526 .def(
527 "getDofs",
528 +[](const dart::dynamics::Skeleton* self)
529 -> std::vector<const dart::dynamics::DegreeOfFreedom*> {
530 return self->getDofs();
531 })
532 .def(
533 "getIndexOf",
534 +[](const dart::dynamics::Skeleton* self,
535 const dart::dynamics::DegreeOfFreedom* _dof) -> std::size_t {
536 return self->getIndexOf(_dof);
537 },
538 ::py::arg("dof"))
539 .def(
540 "getIndexOf",
541 +[](const dart::dynamics::Skeleton* self,
542 const dart::dynamics::DegreeOfFreedom* _dof,
543 bool _warning) -> std::size_t {
544 return self->getIndexOf(_dof, _warning);
545 },
546 ::py::arg("dof"),
547 ::py::arg("warning"))
548 .def(
549 "checkIndexingConsistency",
550 +[](const dart::dynamics::Skeleton* self) -> bool {
551 return self->checkIndexingConsistency();
552 })
553 .def(
554 "getIK",
555 +[](const dart::dynamics::Skeleton* self)
556 -> std::shared_ptr<const dart::dynamics::WholeBodyIK> {
557 return self->getIK();
558 })
559 .def(
560 "clearIK",
561 +[](dart::dynamics::Skeleton* self)
562 -> void { return self->clearIK(); })
563 .def(
564 "getNumMarkers",
565 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
566 return self->getNumMarkers();
567 })
568 .def(
569 "getNumMarkers",
570 +[](const dart::dynamics::Skeleton* self, std::size_t treeIndex)
571 -> std::size_t { return self->getNumMarkers(treeIndex); },
572 ::py::arg("treeIndex"))
573 .def(
574 "getNumShapeNodes",
575 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
576 return self->getNumShapeNodes();
577 })
578 .def(
579 "getNumShapeNodes",
580 +[](const dart::dynamics::Skeleton* self, std::size_t treeIndex)
581 -> std::size_t { return self->getNumShapeNodes(treeIndex); },
582 ::py::arg("treeIndex"))
583 .def(
584 "getShapeNode",
585 +[](dart::dynamics::Skeleton* self,
586 std::size_t index) -> dart::dynamics::ShapeNode* {
587 return self->getShapeNode(index);
588 },
589 ::py::return_value_policy::reference_internal,
590 ::py::arg("index"))
591 .def(
592 "getShapeNode",
593 +[](dart::dynamics::Skeleton* self,
594 const std::string& name) -> dart::dynamics::ShapeNode* {
595 return self->getShapeNode(name);
596 },
597 ::py::return_value_policy::reference_internal,
598 ::py::arg("name"))
599 .def(
600 "getNumEndEffectors",
601 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
602 return self->getNumEndEffectors();
603 })
604 .def(
605 "getNumEndEffectors",
606 +[](const dart::dynamics::Skeleton* self, std::size_t treeIndex)
607 -> std::size_t { return self->getNumEndEffectors(treeIndex); },
608 ::py::arg("treeIndex"))
609 .def(
610 "integratePositions",
611 +[](dart::dynamics::Skeleton* self, double _dt) -> void {
612 return self->integratePositions(_dt);
613 },
614 ::py::arg("dt"))
615 .def(
616 "integrateVelocities",
617 +[](dart::dynamics::Skeleton* self, double _dt) -> void {
618 return self->integrateVelocities(_dt);
619 },
620 ::py::arg("dt"))
621 .def(
622 "getPositionDifferences",
623 +[](const dart::dynamics::Skeleton* self,
624 const Eigen::VectorXd& _q2,
625 const Eigen::VectorXd& _q1) -> Eigen::VectorXd {
626 return self->getPositionDifferences(_q2, _q1);
627 },
628 ::py::arg("q2"),
629 ::py::arg("q1"))
630 .def(
631 "getVelocityDifferences",
632 +[](const dart::dynamics::Skeleton* self,
633 const Eigen::VectorXd& _dq2,
634 const Eigen::VectorXd& _dq1) -> Eigen::VectorXd {
635 return self->getVelocityDifferences(_dq2, _dq1);
636 },
637 ::py::arg("dq2"),
638 ::py::arg("dq1"))
639 .def(
640 "getSupportVersion",
641 +[](const dart::dynamics::Skeleton* self) -> std::size_t {
642 return self->getSupportVersion();
643 })
644 .def(
645 "getSupportVersion",
646 +[](const dart::dynamics::Skeleton* self, std::size_t _treeIdx)
647 -> std::size_t { return self->getSupportVersion(_treeIdx); },
648 ::py::arg("treeIdx"))
649 .def(
650 "computeForwardKinematics",
651 +[](dart::dynamics::Skeleton* self) -> void {
652 return self->computeForwardKinematics();
653 })
654 .def(
655 "computeForwardKinematics",
656 +[](dart::dynamics::Skeleton* self, bool _updateTransforms) -> void {
657 return self->computeForwardKinematics(_updateTransforms);
658 },
659 ::py::arg("updateTransforms"))
660 .def(
661 "computeForwardKinematics",
662 +[](dart::dynamics::Skeleton* self,
663 bool _updateTransforms,
664 bool _updateVels) -> void {
665 return self->computeForwardKinematics(
666 _updateTransforms, _updateVels);
667 },
668 ::py::arg("updateTransforms"),
669 ::py::arg("updateVels"))
670 .def(
671 "computeForwardKinematics",
672 +[](dart::dynamics::Skeleton* self,
673 bool _updateTransforms,
674 bool _updateVels,
675 bool _updateAccs) -> void {
676 return self->computeForwardKinematics(
677 _updateTransforms, _updateVels, _updateAccs);
678 },
679 ::py::arg("updateTransforms"),
680 ::py::arg("updateVels"),
681 ::py::arg("updateAccs"))
682 .def(
683 "computeForwardDynamics",
684 +[](dart::dynamics::Skeleton* self) -> void {
685 return self->computeForwardDynamics();
686 })
687 .def(
688 "computeInverseDynamics",
689 +[](dart::dynamics::Skeleton* self) -> void {
690 return self->computeInverseDynamics();
691 })
692 .def(
693 "computeInverseDynamics",
694 +[](dart::dynamics::Skeleton* self,
695 bool _withExternalForces) -> void {
696 return self->computeInverseDynamics(_withExternalForces);
697 },
698 ::py::arg("withExternalForces"))
699 .def(
700 "computeInverseDynamics",
701 +[](dart::dynamics::Skeleton* self,
702 bool _withExternalForces,
703 bool _withDampingForces) -> void {
704 return self->computeInverseDynamics(
705 _withExternalForces, _withDampingForces);
706 },
707 ::py::arg("withExternalForces"),
708 ::py::arg("withDampingForces"))
709 .def(
710 "computeInverseDynamics",
711 +[](dart::dynamics::Skeleton* self,
712 bool _withExternalForces,
713 bool _withDampingForces,
714 bool _withSpringForces) -> void {
715 return self->computeInverseDynamics(
716 _withExternalForces, _withDampingForces, _withSpringForces);
717 },
718 ::py::arg("withExternalForces"),
719 ::py::arg("withDampingForces"),
720 ::py::arg("withSpringForces"))
721 .def(
722 "clearConstraintImpulses",
723 +[](dart::dynamics::Skeleton* self) -> void {
724 return self->clearConstraintImpulses();
725 })
726 .def(
727 "updateBiasImpulse",
728 +[](dart::dynamics::Skeleton* self,
729 dart::dynamics::BodyNode* _bodyNode) -> void {
730 return self->updateBiasImpulse(_bodyNode);
731 },
732 ::py::arg("bodyNode"))
733 .def(
734 "updateBiasImpulse",
735 +[](dart::dynamics::Skeleton* self,
736 dart::dynamics::BodyNode* _bodyNode,
737 const Eigen::Vector6d& _imp) -> void {
738 return self->updateBiasImpulse(_bodyNode, _imp);
739 },
740 ::py::arg("bodyNode"),
741 ::py::arg("imp"))
742 .def(
743 "updateBiasImpulse",
744 +[](dart::dynamics::Skeleton* self,
745 dart::dynamics::BodyNode* _bodyNode1,
746 const Eigen::Vector6d& _imp1,
747 dart::dynamics::BodyNode* _bodyNode2,
748 const Eigen::Vector6d& _imp2) -> void {
749 return self->updateBiasImpulse(
750 _bodyNode1, _imp1, _bodyNode2, _imp2);
751 },
752 ::py::arg("bodyNode1"),
753 ::py::arg("imp1"),
754 ::py::arg("bodyNode2"),
755 ::py::arg("imp2"))
756 .def(
757 "updateBiasImpulse",
758 +[](dart::dynamics::Skeleton* self,
759 dart::dynamics::SoftBodyNode* _softBodyNode,
760 dart::dynamics::PointMass* _pointMass,
761 const Eigen::Vector3d& _imp) -> void {
762 return self->updateBiasImpulse(_softBodyNode, _pointMass, _imp);
763 },
764 ::py::arg("softBodyNode"),
765 ::py::arg("pointMass"),
766 ::py::arg("imp"))
767 .def(
768 "updateVelocityChange",
769 +[](dart::dynamics::Skeleton* self)
770 -> void { return self->updateVelocityChange(); })
771 .def(
772 "setImpulseApplied",
773 +[](dart::dynamics::Skeleton* self, bool _val) -> void {
774 return self->setImpulseApplied(_val);
775 },
776 ::py::arg("val"))
777 .def(
778 "isImpulseApplied",
779 +[](const dart::dynamics::Skeleton* self) -> bool {
780 return self->isImpulseApplied();
781 })
782 .def(
783 "computeImpulseForwardDynamics",
784 +[](dart::dynamics::Skeleton* self) -> void {
785 return self->computeImpulseForwardDynamics();
786 })
787 .def(
788 "getJacobian",
789 +[](const dart::dynamics::Skeleton* self,
790 const dart::dynamics::JacobianNode* _node)
791 -> dart::math::Jacobian { return self->getJacobian(_node); },
792 ::py::arg("node"))
793 .def(
794 "getJacobian",
795 +[](const dart::dynamics::Skeleton* self,
796 const dart::dynamics::JacobianNode* _node,
797 const dart::dynamics::Frame* _inCoordinatesOf)
798 -> dart::math::Jacobian {
799 return self->getJacobian(_node, _inCoordinatesOf);
800 },
801 ::py::arg("node"),
802 ::py::arg("inCoordinatesOf"))
803 .def(
804 "getJacobian",
805 +[](const dart::dynamics::Skeleton* self,
806 const dart::dynamics::JacobianNode* _node,
807 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
808 return self->getJacobian(_node, _localOffset);
809 },
810 ::py::arg("node"),
811 ::py::arg("localOffset"))
812 .def(
813 "getJacobian",
814 +[](const dart::dynamics::Skeleton* self,
815 const dart::dynamics::JacobianNode* _node,
816 const Eigen::Vector3d& _localOffset,
817 const dart::dynamics::Frame* _inCoordinatesOf)
818 -> dart::math::Jacobian {
819 return self->getJacobian(_node, _localOffset, _inCoordinatesOf);
820 },
821 ::py::arg("node"),
822 ::py::arg("localOffset"),
823 ::py::arg("inCoordinatesOf"))
824 .def(
825 "getWorldJacobian",
826 +[](const dart::dynamics::Skeleton* self,
827 const dart::dynamics::JacobianNode* _node)
828 -> dart::math::Jacobian { return self->getWorldJacobian(_node); },
829 ::py::arg("node"))
830 .def(
831 "getWorldJacobian",
832 +[](const dart::dynamics::Skeleton* self,
833 const dart::dynamics::JacobianNode* _node,
834 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
835 return self->getWorldJacobian(_node, _localOffset);
836 },
837 ::py::arg("node"),
838 ::py::arg("localOffset"))
839 .def(
840 "getLinearJacobian",
841 +[](const dart::dynamics::Skeleton* self,
842 const dart::dynamics::JacobianNode* _node)
843 -> dart::math::LinearJacobian {
844 return self->getLinearJacobian(_node);
845 },
846 ::py::arg("node"))
847 .def(
848 "getLinearJacobian",
849 +[](const dart::dynamics::Skeleton* self,
850 const dart::dynamics::JacobianNode* _node,
851 const dart::dynamics::Frame* _inCoordinatesOf)
852 -> dart::math::LinearJacobian {
853 return self->getLinearJacobian(_node, _inCoordinatesOf);
854 },
855 ::py::arg("node"),
856 ::py::arg("inCoordinatesOf"))
857 .def(
858 "getLinearJacobian",
859 +[](const dart::dynamics::Skeleton* self,
860 const dart::dynamics::JacobianNode* _node,
861 const Eigen::Vector3d& _localOffset)
862 -> dart::math::LinearJacobian {
863 return self->getLinearJacobian(_node, _localOffset);
864 },
865 ::py::arg("node"),
866 ::py::arg("localOffset"))
867 .def(
868 "getLinearJacobian",
869 +[](const dart::dynamics::Skeleton* self,
870 const dart::dynamics::JacobianNode* _node,
871 const Eigen::Vector3d& _localOffset,
872 const dart::dynamics::Frame* _inCoordinatesOf)
873 -> dart::math::LinearJacobian {
874 return self->getLinearJacobian(
875 _node, _localOffset, _inCoordinatesOf);
876 },
877 ::py::arg("node"),
878 ::py::arg("localOffset"),
879 ::py::arg("inCoordinatesOf"))
880 .def(
881 "getAngularJacobian",
882 +[](const dart::dynamics::Skeleton* self,
883 const dart::dynamics::JacobianNode* _node)
884 -> dart::math::AngularJacobian {
885 return self->getAngularJacobian(_node);
886 },
887 ::py::arg("node"))
888 .def(
889 "getAngularJacobian",
890 +[](const dart::dynamics::Skeleton* self,
891 const dart::dynamics::JacobianNode* _node,
892 const dart::dynamics::Frame* _inCoordinatesOf)
893 -> dart::math::AngularJacobian {
894 return self->getAngularJacobian(_node, _inCoordinatesOf);
895 },
896 ::py::arg("node"),
897 ::py::arg("inCoordinatesOf"))
898 .def(
899 "getJacobianSpatialDeriv",
900 +[](const dart::dynamics::Skeleton* self,
901 const dart::dynamics::JacobianNode* _node)
902 -> dart::math::Jacobian {
903 return self->getJacobianSpatialDeriv(_node);
904 },
905 ::py::arg("node"))
906 .def(
907 "getJacobianSpatialDeriv",
908 +[](const dart::dynamics::Skeleton* self,
909 const dart::dynamics::JacobianNode* _node,
910 const dart::dynamics::Frame* _inCoordinatesOf)
911 -> dart::math::Jacobian {
912 return self->getJacobianSpatialDeriv(_node, _inCoordinatesOf);
913 },
914 ::py::arg("node"),
915 ::py::arg("inCoordinatesOf"))
916 .def(
917 "getJacobianSpatialDeriv",
918 +[](const dart::dynamics::Skeleton* self,
919 const dart::dynamics::JacobianNode* _node,
920 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
921 return self->getJacobianSpatialDeriv(_node, _localOffset);
922 },
923 ::py::arg("node"),
924 ::py::arg("localOffset"))
925 .def(
926 "getJacobianSpatialDeriv",
927 +[](const dart::dynamics::Skeleton* self,
928 const dart::dynamics::JacobianNode* _node,
929 const Eigen::Vector3d& _localOffset,
930 const dart::dynamics::Frame* _inCoordinatesOf)
931 -> dart::math::Jacobian {
932 return self->getJacobianSpatialDeriv(
933 _node, _localOffset, _inCoordinatesOf);
934 },
935 ::py::arg("node"),
936 ::py::arg("localOffset"),
937 ::py::arg("inCoordinatesOf"))
938 .def(
939 "getJacobianClassicDeriv",
940 +[](const dart::dynamics::Skeleton* self,
941 const dart::dynamics::JacobianNode* _node)
942 -> dart::math::Jacobian {
943 return self->getJacobianClassicDeriv(_node);
944 },
945 ::py::arg("node"))
946 .def(
947 "getJacobianClassicDeriv",
948 +[](const dart::dynamics::Skeleton* self,
949 const dart::dynamics::JacobianNode* _node,
950 const dart::dynamics::Frame* _inCoordinatesOf)
951 -> dart::math::Jacobian {
952 return self->getJacobianClassicDeriv(_node, _inCoordinatesOf);
953 },
954 ::py::arg("node"),
955 ::py::arg("inCoordinatesOf"))
956 .def(
957 "getJacobianClassicDeriv",
958 +[](const dart::dynamics::Skeleton* self,
959 const dart::dynamics::JacobianNode* _node,
960 const Eigen::Vector3d& _localOffset) -> dart::math::Jacobian {
961 return self->getJacobianClassicDeriv(_node, _localOffset);
962 },
963 ::py::arg("node"),
964 ::py::arg("localOffset"))
965 .def(
966 "getJacobianClassicDeriv",
967 +[](const dart::dynamics::Skeleton* self,
968 const dart::dynamics::JacobianNode* _node,
969 const Eigen::Vector3d& _localOffset,
970 const dart::dynamics::Frame* _inCoordinatesOf)
971 -> dart::math::Jacobian {
972 return self->getJacobianClassicDeriv(
973 _node, _localOffset, _inCoordinatesOf);
974 },
975 ::py::arg("node"),
976 ::py::arg("localOffset"),
977 ::py::arg("inCoordinatesOf"))
978 .def(
979 "getLinearJacobianDeriv",
980 +[](const dart::dynamics::Skeleton* self,
981 const dart::dynamics::JacobianNode* _node)
982 -> dart::math::LinearJacobian {
983 return self->getLinearJacobianDeriv(_node);
984 },
985 ::py::arg("node"))
986 .def(
987 "getLinearJacobianDeriv",
988 +[](const dart::dynamics::Skeleton* self,
989 const dart::dynamics::JacobianNode* _node,
990 const dart::dynamics::Frame* _inCoordinatesOf)
991 -> dart::math::LinearJacobian {
992 return self->getLinearJacobianDeriv(_node, _inCoordinatesOf);
993 },
994 ::py::arg("node"),
995 ::py::arg("inCoordinatesOf"))
996 .def(
997 "getLinearJacobianDeriv",
998 +[](const dart::dynamics::Skeleton* self,
999 const dart::dynamics::JacobianNode* _node,
1000 const Eigen::Vector3d& _localOffset)
1001 -> dart::math::LinearJacobian {
1002 return self->getLinearJacobianDeriv(_node, _localOffset);
1003 },
1004 ::py::arg("node"),
1005 ::py::arg("localOffset"))
1006 .def(
1007 "getLinearJacobianDeriv",
1008 +[](const dart::dynamics::Skeleton* self,
1009 const dart::dynamics::JacobianNode* _node,
1010 const Eigen::Vector3d& _localOffset,
1011 const dart::dynamics::Frame* _inCoordinatesOf)
1012 -> dart::math::LinearJacobian {
1013 return self->getLinearJacobianDeriv(
1014 _node, _localOffset, _inCoordinatesOf);
1015 },
1016 ::py::arg("node"),
1017 ::py::arg("localOffset"),
1018 ::py::arg("inCoordinatesOf"))
1019 .def(
1020 "getAngularJacobianDeriv",
1021 +[](const dart::dynamics::Skeleton* self,
1022 const dart::dynamics::JacobianNode* _node)
1023 -> dart::math::AngularJacobian {
1024 return self->getAngularJacobianDeriv(_node);
1025 },
1026 ::py::arg("node"))
1027 .def(
1028 "getAngularJacobianDeriv",
1029 +[](const dart::dynamics::Skeleton* self,
1030 const dart::dynamics::JacobianNode* _node,
1031 const dart::dynamics::Frame* _inCoordinatesOf)
1032 -> dart::math::AngularJacobian {
1033 return self->getAngularJacobianDeriv(_node, _inCoordinatesOf);
1034 },
1035 ::py::arg("node"),
1036 ::py::arg("inCoordinatesOf"))
1037 .def(
1038 "getMass",
1039 +[](const dart::dynamics::Skeleton* self)
1040 -> double { return self->getMass(); })
1041 .def(
1042 "getMassMatrix",
1043 +[](const dart::dynamics::Skeleton* self,
1044 std::size_t treeIndex) -> const Eigen::MatrixXd& {
1045 return self->getMassMatrix(treeIndex);
1046 })
1047 // TODO(JS): Redefining get[~]() that are already defined in MetaSkeleton.
1048 // We need this because the methods with same name (but different
1049 // arguments) are hidden. Update (or remove) once following issue is
1050 // resolved: https://github.com/pybind/pybind11/issues/974
1051 .def(
1052 "getMassMatrix",
1053 +[](const dart::dynamics::Skeleton* self) -> const Eigen::MatrixXd& {
1054 return self->getMassMatrix();
1055 })
1056 .def(
1057 "getAugMassMatrix",
1058 +[](const dart::dynamics::Skeleton* self,
1059 std::size_t treeIndex) -> const Eigen::MatrixXd& {
1060 return self->getAugMassMatrix(treeIndex);
1061 })
1062 .def(
1063 "getAugMassMatrix",
1064 +[](const dart::dynamics::Skeleton* self) -> const Eigen::MatrixXd& {
1065 return self->getAugMassMatrix();
1066 })
1067 .def(
1068 "getInvMassMatrix",
1069 +[](const dart::dynamics::Skeleton* self,
1070 std::size_t treeIndex) -> const Eigen::MatrixXd& {
1071 return self->getInvMassMatrix(treeIndex);
1072 })
1073 .def(
1074 "getInvMassMatrix",
1075 +[](const dart::dynamics::Skeleton* self) -> const Eigen::MatrixXd& {
1076 return self->getInvMassMatrix();
1077 })
1078 .def(
1079 "getCoriolisForces",
1080 +[](dart::dynamics::Skeleton* self,
1081 std::size_t treeIndex) -> const Eigen::VectorXd& {
1082 return self->getCoriolisForces(treeIndex);
1083 })
1084 .def(
1085 "getCoriolisForces",
1086 +[](dart::dynamics::Skeleton* self) -> const Eigen::VectorXd& {
1087 return self->getCoriolisForces();
1088 })
1089 .def(
1090 "getGravityForces",
1091 +[](dart::dynamics::Skeleton* self,
1092 std::size_t treeIndex) -> const Eigen::VectorXd& {
1093 return self->getGravityForces(treeIndex);
1094 })
1095 .def(
1096 "getGravityForces",
1097 +[](dart::dynamics::Skeleton* self) -> const Eigen::VectorXd& {
1098 return self->getGravityForces();
1099 })
1100 .def(
1101 "getCoriolisAndGravityForces",
1102 +[](dart::dynamics::Skeleton* self,
1103 std::size_t treeIndex) -> const Eigen::VectorXd& {
1104 return self->getCoriolisAndGravityForces(treeIndex);
1105 })
1106 .def(
1107 "getCoriolisAndGravityForces",
1108 +[](dart::dynamics::Skeleton* self) -> const Eigen::VectorXd& {
1109 return self->getCoriolisAndGravityForces();
1110 })
1111 .def(
1112 "getExternalForces",
1113 +[](dart::dynamics::Skeleton* self,
1114 std::size_t treeIndex) -> const Eigen::VectorXd& {
1115 return self->getExternalForces(treeIndex);
1116 })
1117 .def(
1118 "getExternalForces",
1119 +[](dart::dynamics::Skeleton* self) -> const Eigen::VectorXd& {
1120 return self->getExternalForces();
1121 })
1122 .def(
1123 "getConstraintForces",
1124 +[](dart::dynamics::Skeleton* self,
1125 std::size_t treeIndex) -> const Eigen::VectorXd& {
1126 return self->getConstraintForces(treeIndex);
1127 })
1128 .def(
1129 "getConstraintForces",
1130 +[](dart::dynamics::Skeleton* self) -> const Eigen::VectorXd& {
1131 return self->getConstraintForces();
1132 })
1133 .def(
1134 "clearExternalForces",
1135 +[](dart::dynamics::Skeleton* self)
1136 -> void { return self->clearExternalForces(); })
1137 .def(
1138 "clearInternalForces",
1139 +[](dart::dynamics::Skeleton* self)
1140 -> void { return self->clearInternalForces(); })
1141 // .def("notifyArticulatedInertiaUpdate",
1142 // +[](dart::dynamics::Skeleton *self, std::size_t _treeIdx) -> void
1143 // { return self->notifyArticulatedInertiaUpdate(_treeIdx); },
1144 // ::py::arg("treeIdx"))
1145 .def(
1146 "dirtyArticulatedInertia",
1147 +[](dart::dynamics::Skeleton* self, std::size_t _treeIdx) -> void {
1148 return self->dirtyArticulatedInertia(_treeIdx);
1149 },
1150 ::py::arg("treeIdx"))
1151 // .def("notifySupportUpdate", +[](dart::dynamics::Skeleton *self,
1152 // std::size_t _treeIdx) -> void { return
1153 // self->notifySupportUpdate(_treeIdx); },
1154 // ::py::arg("treeIdx"))
1155 .def(
1156 "dirtySupportPolygon",
1157 +[](dart::dynamics::Skeleton* self, std::size_t _treeIdx) -> void {
1158 return self->dirtySupportPolygon(_treeIdx);
1159 },
1160 ::py::arg("treeIdx"))
1161 .def(
1162 "computeKineticEnergy",
1163 +[](const dart::dynamics::Skeleton* self) -> double {
1164 return self->computeKineticEnergy();
1165 })
1166 .def(
1167 "computePotentialEnergy",
1168 +[](const dart::dynamics::Skeleton* self) -> double {
1169 return self->computePotentialEnergy();
1170 })
1171 // .def("clearCollidingBodies", +[](dart::dynamics::Skeleton *self)
1172 // -> void { return self->clearCollidingBodies(); })
1173 .def(
1174 "getCOM",
1175 +[](const dart::dynamics::Skeleton* self) -> Eigen::Vector3d {
1176 return self->getCOM();
1177 })
1178 .def(
1179 "getCOM",
1180 +[](const dart::dynamics::Skeleton* self,
1181 const dart::dynamics::Frame* _withRespectTo) -> Eigen::Vector3d {
1182 return self->getCOM(_withRespectTo);
1183 },
1184 ::py::arg("withRespectTo"))
1185 .def(
1186 "getCOMSpatialVelocity",
1187 +[](const dart::dynamics::Skeleton* self) -> Eigen::Vector6d {
1188 return self->getCOMSpatialVelocity();
1189 })
1190 .def(
1191 "getCOMSpatialVelocity",
1192 +[](const dart::dynamics::Skeleton* self,
1193 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector6d {
1194 return self->getCOMSpatialVelocity(_relativeTo);
1195 },
1196 ::py::arg("relativeTo"))
1197 .def(
1198 "getCOMSpatialVelocity",
1199 +[](const dart::dynamics::Skeleton* self,
1200 const dart::dynamics::Frame* _relativeTo,
1201 const dart::dynamics::Frame* _inCoordinatesOf)
1202 -> Eigen::Vector6d {
1203 return self->getCOMSpatialVelocity(_relativeTo, _inCoordinatesOf);
1204 },
1205 ::py::arg("relativeTo"),
1206 ::py::arg("inCoordinatesOf"))
1207 .def(
1208 "getCOMLinearVelocity",
1209 +[](const dart::dynamics::Skeleton* self) -> Eigen::Vector3d {
1210 return self->getCOMLinearVelocity();
1211 })
1212 .def(
1213 "getCOMLinearVelocity",
1214 +[](const dart::dynamics::Skeleton* self,
1215 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector3d {
1216 return self->getCOMLinearVelocity(_relativeTo);
1217 },
1218 ::py::arg("relativeTo"))
1219 .def(
1220 "getCOMLinearVelocity",
1221 +[](const dart::dynamics::Skeleton* self,
1222 const dart::dynamics::Frame* _relativeTo,
1223 const dart::dynamics::Frame* _inCoordinatesOf)
1224 -> Eigen::Vector3d {
1225 return self->getCOMLinearVelocity(_relativeTo, _inCoordinatesOf);
1226 },
1227 ::py::arg("relativeTo"),
1228 ::py::arg("inCoordinatesOf"))
1229 .def(
1230 "getCOMSpatialAcceleration",
1231 +[](const dart::dynamics::Skeleton* self) -> Eigen::Vector6d {
1232 return self->getCOMSpatialAcceleration();
1233 })
1234 .def(
1235 "getCOMSpatialAcceleration",
1236 +[](const dart::dynamics::Skeleton* self,
1237 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector6d {
1238 return self->getCOMSpatialAcceleration(_relativeTo);
1239 },
1240 ::py::arg("relativeTo"))
1241 .def(
1242 "getCOMSpatialAcceleration",
1243 +[](const dart::dynamics::Skeleton* self,
1244 const dart::dynamics::Frame* _relativeTo,
1245 const dart::dynamics::Frame* _inCoordinatesOf)
1246 -> Eigen::Vector6d {
1247 return self->getCOMSpatialAcceleration(
1248 _relativeTo, _inCoordinatesOf);
1249 },
1250 ::py::arg("relativeTo"),
1251 ::py::arg("inCoordinatesOf"))
1252 .def(
1253 "getCOMLinearAcceleration",
1254 +[](const dart::dynamics::Skeleton* self) -> Eigen::Vector3d {
1255 return self->getCOMLinearAcceleration();
1256 })
1257 .def(
1258 "getCOMLinearAcceleration",
1259 +[](const dart::dynamics::Skeleton* self,
1260 const dart::dynamics::Frame* _relativeTo) -> Eigen::Vector3d {
1261 return self->getCOMLinearAcceleration(_relativeTo);
1262 },
1263 ::py::arg("relativeTo"))
1264 .def(
1265 "getCOMLinearAcceleration",
1266 +[](const dart::dynamics::Skeleton* self,
1267 const dart::dynamics::Frame* _relativeTo,
1268 const dart::dynamics::Frame* _inCoordinatesOf)
1269 -> Eigen::Vector3d {
1270 return self->getCOMLinearAcceleration(
1271 _relativeTo, _inCoordinatesOf);
1272 },
1273 ::py::arg("relativeTo"),
1274 ::py::arg("inCoordinatesOf"))
1275 .def(
1276 "getCOMJacobian",
1277 +[](const dart::dynamics::Skeleton* self) -> dart::math::Jacobian {
1278 return self->getCOMJacobian();
1279 })
1280 .def(
1281 "getCOMJacobian",
1282 +[](const dart::dynamics::Skeleton* self,
1283 const dart::dynamics::Frame* _inCoordinatesOf)
1284 -> dart::math::Jacobian {
1285 return self->getCOMJacobian(_inCoordinatesOf);
1286 },
1287 ::py::arg("inCoordinatesOf"))
1288 .def(
1289 "getCOMLinearJacobian",
1290 +[](const dart::dynamics::Skeleton* self)
1291 -> dart::math::LinearJacobian {
1292 return self->getCOMLinearJacobian();
1293 })
1294 .def(
1295 "getCOMLinearJacobian",
1296 +[](const dart::dynamics::Skeleton* self,
1297 const dart::dynamics::Frame* _inCoordinatesOf)
1298 -> dart::math::LinearJacobian {
1299 return self->getCOMLinearJacobian(_inCoordinatesOf);
1300 },
1301 ::py::arg("inCoordinatesOf"))
1302 .def(
1303 "getCOMJacobianSpatialDeriv",
1304 +[](const dart::dynamics::Skeleton* self) -> dart::math::Jacobian {
1305 return self->getCOMJacobianSpatialDeriv();
1306 })
1307 .def(
1308 "getCOMJacobianSpatialDeriv",
1309 +[](const dart::dynamics::Skeleton* self,
1310 const dart::dynamics::Frame* _inCoordinatesOf)
1311 -> dart::math::Jacobian {
1312 return self->getCOMJacobianSpatialDeriv(_inCoordinatesOf);
1313 },
1314 ::py::arg("inCoordinatesOf"))
1315 .def(
1316 "getCOMLinearJacobianDeriv",
1317 +[](const dart::dynamics::Skeleton* self)
1318 -> dart::math::LinearJacobian {
1319 return self->getCOMLinearJacobianDeriv();
1320 })
1321 .def(
1322 "getCOMLinearJacobianDeriv",
1323 +[](const dart::dynamics::Skeleton* self,
1324 const dart::dynamics::Frame* _inCoordinatesOf)
1325 -> dart::math::LinearJacobian {
1326 return self->getCOMLinearJacobianDeriv(_inCoordinatesOf);
1327 },
1328 ::py::arg("inCoordinatesOf"))
1329 .def(
1330 "resetUnion",
1331 +[](dart::dynamics::Skeleton* self)
1332 -> void { return self->resetUnion(); })
1333 .def_readwrite(
1334 "mUnionRootSkeleton", &dart::dynamics::Skeleton::mUnionRootSkeleton)
1335 .def_readwrite("mUnionSize", &dart::dynamics::Skeleton::mUnionSize)
1336 .def_readwrite("mUnionIndex", &dart::dynamics::Skeleton::mUnionIndex);
1337 }
1338
1339 } // namespace python
1340 } // namespace dart
1341