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 <eigen_geometry_pybind.h>
35 #include <pybind11/eigen.h>
36 #include <pybind11/pybind11.h>
37 #include "Joint.hpp"
38
39 namespace py = pybind11;
40
41 namespace dart {
42 namespace python {
43
ZeroDofJoint(py::module & m)44 void ZeroDofJoint(py::module& m)
45 {
46 ::py::class_<dart::dynamics::ZeroDofJoint::Properties>(
47 m, "ZeroDofJointProperties")
48 .def(::py::init<>())
49 .def(
50 ::py::init<const dart::dynamics::Joint::Properties&>(),
51 ::py::arg("properties"));
52
53 ::py::class_<
54 dart::dynamics::ZeroDofJoint,
55 dart::dynamics::Joint,
56 std::shared_ptr<dart::dynamics::ZeroDofJoint> >(m, "ZeroDofJoint")
57 .def(
58 "getZeroDofJointProperties",
59 +[](const dart::dynamics::ZeroDofJoint* self)
60 -> dart::dynamics::ZeroDofJoint::Properties {
61 return self->getZeroDofJointProperties();
62 })
63 .def(
64 "setDofName",
65 +[](dart::dynamics::ZeroDofJoint* self,
66 std::size_t _arg0_,
67 const std::string& _arg1_,
68 bool _arg2_) -> const std::string& {
69 return self->setDofName(_arg0_, _arg1_, _arg2_);
70 },
71 ::py::return_value_policy::reference_internal,
72 ::py::arg("arg0_"),
73 ::py::arg("arg1_"),
74 ::py::arg("arg2_"))
75 .def(
76 "preserveDofName",
77 +[](dart::dynamics::ZeroDofJoint* self,
78 std::size_t _arg0_,
79 bool _arg1_) { self->preserveDofName(_arg0_, _arg1_); },
80 ::py::arg("arg0_"),
81 ::py::arg("arg1_"))
82 .def(
83 "isDofNamePreserved",
84 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _arg0_)
85 -> bool { return self->isDofNamePreserved(_arg0_); },
86 ::py::arg("arg0_"))
87 .def(
88 "getDofName",
89 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _arg0_)
90 -> const std::string& { return self->getDofName(_arg0_); },
91 ::py::return_value_policy::reference_internal,
92 ::py::arg("arg0_"))
93 .def(
94 "getNumDofs",
95 +[](const dart::dynamics::ZeroDofJoint* self) -> std::size_t {
96 return self->getNumDofs();
97 })
98 .def(
99 "getIndexInSkeleton",
100 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
101 -> std::size_t { return self->getIndexInSkeleton(_index); },
102 ::py::arg("index"))
103 .def(
104 "getIndexInTree",
105 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
106 -> std::size_t { return self->getIndexInTree(_index); },
107 ::py::arg("index"))
108 .def(
109 "setCommand",
110 +[](dart::dynamics::ZeroDofJoint* self,
111 std::size_t _index,
112 double _command) { self->setCommand(_index, _command); },
113 ::py::arg("index"),
114 ::py::arg("command"))
115 .def(
116 "getCommand",
117 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
118 -> double { return self->getCommand(_index); },
119 ::py::arg("index"))
120 .def(
121 "setCommands",
122 +[](dart::dynamics::ZeroDofJoint* self,
123 const Eigen::VectorXd& _commands) {
124 self->setCommands(_commands);
125 },
126 ::py::arg("commands"))
127 .def(
128 "getCommands",
129 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
130 return self->getCommands();
131 })
132 .def(
133 "resetCommands",
134 +[](dart::dynamics::ZeroDofJoint* self) { self->resetCommands(); })
135 .def(
136 "setPosition",
137 +[](dart::dynamics::ZeroDofJoint* self,
138 std::size_t _arg0_,
139 double _arg1_) { self->setPosition(_arg0_, _arg1_); },
140 ::py::arg("arg0_"),
141 ::py::arg("arg1_"))
142 .def(
143 "getPosition",
144 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
145 -> double { return self->getPosition(_index); },
146 ::py::arg("index"))
147 .def(
148 "setPositions",
149 +[](dart::dynamics::ZeroDofJoint* self,
150 const Eigen::VectorXd& _positions) {
151 self->setPositions(_positions);
152 },
153 ::py::arg("positions"))
154 .def(
155 "getPositions",
156 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
157 return self->getPositions();
158 })
159 .def(
160 "setPositionLowerLimit",
161 +[](dart::dynamics::ZeroDofJoint* self,
162 std::size_t _index,
163 double _position) {
164 self->setPositionLowerLimit(_index, _position);
165 },
166 ::py::arg("index"),
167 ::py::arg("position"))
168 .def(
169 "getPositionLowerLimit",
170 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
171 -> double { return self->getPositionLowerLimit(_index); },
172 ::py::arg("index"))
173 .def(
174 "setPositionLowerLimits",
175 +[](dart::dynamics::ZeroDofJoint* self,
176 const Eigen::VectorXd& lowerLimits) {
177 self->setPositionLowerLimits(lowerLimits);
178 },
179 ::py::arg("lowerLimits"))
180 .def(
181 "getPositionLowerLimits",
182 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
183 return self->getPositionLowerLimits();
184 })
185 .def(
186 "setPositionUpperLimit",
187 +[](dart::dynamics::ZeroDofJoint* self,
188 std::size_t index,
189 double position) {
190 self->setPositionUpperLimit(index, position);
191 },
192 ::py::arg("index"),
193 ::py::arg("position"))
194 .def(
195 "getPositionUpperLimit",
196 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t index)
197 -> double { return self->getPositionUpperLimit(index); },
198 ::py::arg("index"))
199 .def(
200 "setPositionUpperLimits",
201 +[](dart::dynamics::ZeroDofJoint* self,
202 const Eigen::VectorXd& upperLimits) {
203 self->setPositionUpperLimits(upperLimits);
204 },
205 ::py::arg("upperLimits"))
206 .def(
207 "getPositionUpperLimits",
208 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
209 return self->getPositionUpperLimits();
210 })
211 .def(
212 "hasPositionLimit",
213 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
214 -> bool { return self->hasPositionLimit(_index); },
215 ::py::arg("index"))
216 .def(
217 "resetPosition",
218 +[](dart::dynamics::ZeroDofJoint* self, std::size_t _index) {
219 self->resetPosition(_index);
220 },
221 ::py::arg("index"))
222 .def(
223 "resetPositions",
224 +[](dart::dynamics::ZeroDofJoint* self) { self->resetPositions(); })
225 .def(
226 "setInitialPosition",
227 +[](dart::dynamics::ZeroDofJoint* self,
228 std::size_t _index,
229 double _initial) { self->setInitialPosition(_index, _initial); },
230 ::py::arg("index"),
231 ::py::arg("initial"))
232 .def(
233 "getInitialPosition",
234 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
235 -> double { return self->getInitialPosition(_index); },
236 ::py::arg("index"))
237 .def(
238 "setInitialPositions",
239 +[](dart::dynamics::ZeroDofJoint* self,
240 const Eigen::VectorXd& _initial) {
241 self->setInitialPositions(_initial);
242 },
243 ::py::arg("initial"))
244 .def(
245 "getInitialPositions",
246 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
247 return self->getInitialPositions();
248 })
249 .def(
250 "setVelocity",
251 +[](dart::dynamics::ZeroDofJoint* self,
252 std::size_t _index,
253 double _velocity) { self->setVelocity(_index, _velocity); },
254 ::py::arg("index"),
255 ::py::arg("velocity"))
256 .def(
257 "getVelocity",
258 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
259 -> double { return self->getVelocity(_index); },
260 ::py::arg("index"))
261 .def(
262 "setVelocities",
263 +[](dart::dynamics::ZeroDofJoint* self,
264 const Eigen::VectorXd& _velocities) {
265 self->setVelocities(_velocities);
266 },
267 ::py::arg("velocities"))
268 .def(
269 "getVelocities",
270 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
271 return self->getVelocities();
272 })
273 .def(
274 "setVelocityLowerLimit",
275 +[](dart::dynamics::ZeroDofJoint* self,
276 std::size_t _index,
277 double _velocity) {
278 self->setVelocityLowerLimit(_index, _velocity);
279 },
280 ::py::arg("index"),
281 ::py::arg("velocity"))
282 .def(
283 "getVelocityLowerLimit",
284 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
285 -> double { return self->getVelocityLowerLimit(_index); },
286 ::py::arg("index"))
287 .def(
288 "setVelocityLowerLimits",
289 +[](dart::dynamics::ZeroDofJoint* self,
290 const Eigen::VectorXd& lowerLimits) {
291 self->setVelocityLowerLimits(lowerLimits);
292 },
293 ::py::arg("lowerLimits"))
294 .def(
295 "getVelocityLowerLimits",
296 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
297 return self->getVelocityLowerLimits();
298 })
299 .def(
300 "setVelocityUpperLimit",
301 +[](dart::dynamics::ZeroDofJoint* self,
302 std::size_t _index,
303 double _velocity) {
304 self->setVelocityUpperLimit(_index, _velocity);
305 },
306 ::py::arg("index"),
307 ::py::arg("velocity"))
308 .def(
309 "getVelocityUpperLimit",
310 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
311 -> double { return self->getVelocityUpperLimit(_index); },
312 ::py::arg("index"))
313 .def(
314 "setVelocityUpperLimits",
315 +[](dart::dynamics::ZeroDofJoint* self,
316 const Eigen::VectorXd& upperLimits) {
317 self->setVelocityUpperLimits(upperLimits);
318 },
319 ::py::arg("upperLimits"))
320 .def(
321 "getVelocityUpperLimits",
322 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
323 return self->getVelocityUpperLimits();
324 })
325 .def(
326 "resetVelocity",
327 +[](dart::dynamics::ZeroDofJoint* self, std::size_t _index) {
328 self->resetVelocity(_index);
329 },
330 ::py::arg("index"))
331 .def(
332 "resetVelocities",
333 +[](dart::dynamics::ZeroDofJoint* self) { self->resetVelocities(); })
334 .def(
335 "setInitialVelocity",
336 +[](dart::dynamics::ZeroDofJoint* self,
337 std::size_t _index,
338 double _initial) { self->setInitialVelocity(_index, _initial); },
339 ::py::arg("index"),
340 ::py::arg("initial"))
341 .def(
342 "getInitialVelocity",
343 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
344 -> double { return self->getInitialVelocity(_index); },
345 ::py::arg("index"))
346 .def(
347 "setInitialVelocities",
348 +[](dart::dynamics::ZeroDofJoint* self,
349 const Eigen::VectorXd& _initial) {
350 self->setInitialVelocities(_initial);
351 },
352 ::py::arg("initial"))
353 .def(
354 "getInitialVelocities",
355 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
356 return self->getInitialVelocities();
357 })
358 .def(
359 "setAcceleration",
360 +[](dart::dynamics::ZeroDofJoint* self,
361 std::size_t _index,
362 double _acceleration) {
363 self->setAcceleration(_index, _acceleration);
364 },
365 ::py::arg("index"),
366 ::py::arg("acceleration"))
367 .def(
368 "getAcceleration",
369 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
370 -> double { return self->getAcceleration(_index); },
371 ::py::arg("index"))
372 .def(
373 "setAccelerations",
374 +[](dart::dynamics::ZeroDofJoint* self,
375 const Eigen::VectorXd& _accelerations) {
376 self->setAccelerations(_accelerations);
377 },
378 ::py::arg("accelerations"))
379 .def(
380 "getAccelerations",
381 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
382 return self->getAccelerations();
383 })
384 .def(
385 "resetAccelerations",
386 +[](dart::dynamics::ZeroDofJoint* self) {
387 self->resetAccelerations();
388 })
389 .def(
390 "setAccelerationLowerLimit",
391 +[](dart::dynamics::ZeroDofJoint* self,
392 std::size_t _index,
393 double _acceleration) {
394 self->setAccelerationLowerLimit(_index, _acceleration);
395 },
396 ::py::arg("index"),
397 ::py::arg("acceleration"))
398 .def(
399 "getAccelerationLowerLimit",
400 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
401 -> double { return self->getAccelerationLowerLimit(_index); },
402 ::py::arg("index"))
403 .def(
404 "setAccelerationLowerLimits",
405 +[](dart::dynamics::ZeroDofJoint* self,
406 const Eigen::VectorXd& lowerLimits) {
407 self->setAccelerationLowerLimits(lowerLimits);
408 },
409 ::py::arg("lowerLimits"))
410 .def(
411 "getAccelerationLowerLimits",
412 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
413 return self->getAccelerationLowerLimits();
414 })
415 .def(
416 "setAccelerationUpperLimit",
417 +[](dart::dynamics::ZeroDofJoint* self,
418 std::size_t _index,
419 double _acceleration) {
420 self->setAccelerationUpperLimit(_index, _acceleration);
421 },
422 ::py::arg("index"),
423 ::py::arg("acceleration"))
424 .def(
425 "getAccelerationUpperLimit",
426 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
427 -> double { return self->getAccelerationUpperLimit(_index); },
428 ::py::arg("index"))
429 .def(
430 "setAccelerationUpperLimits",
431 +[](dart::dynamics::ZeroDofJoint* self,
432 const Eigen::VectorXd& upperLimits) {
433 self->setAccelerationUpperLimits(upperLimits);
434 },
435 ::py::arg("upperLimits"))
436 .def(
437 "getAccelerationUpperLimits",
438 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
439 return self->getAccelerationUpperLimits();
440 })
441 .def(
442 "setForce",
443 +[](dart::dynamics::ZeroDofJoint* self,
444 std::size_t _index,
445 double _force) { self->setForce(_index, _force); },
446 ::py::arg("index"),
447 ::py::arg("force"))
448 .def(
449 "getForce",
450 +[](const dart::dynamics::ZeroDofJoint* self,
451 std::size_t _index) -> double { return self->getForce(_index); },
452 ::py::arg("index"))
453 .def(
454 "setForces",
455 +[](dart::dynamics::ZeroDofJoint* self,
456 const Eigen::VectorXd& _forces) { self->setForces(_forces); },
457 ::py::arg("forces"))
458 .def(
459 "getForces",
460 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
461 return self->getForces();
462 })
463 .def(
464 "resetForces",
465 +[](dart::dynamics::ZeroDofJoint* self) { self->resetForces(); })
466 .def(
467 "setForceLowerLimit",
468 +[](dart::dynamics::ZeroDofJoint* self,
469 std::size_t _index,
470 double _force) { self->setForceLowerLimit(_index, _force); },
471 ::py::arg("index"),
472 ::py::arg("force"))
473 .def(
474 "getForceLowerLimit",
475 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
476 -> double { return self->getForceLowerLimit(_index); },
477 ::py::arg("index"))
478 .def(
479 "setForceLowerLimits",
480 +[](dart::dynamics::ZeroDofJoint* self,
481 const Eigen::VectorXd& lowerLimits) {
482 self->setForceLowerLimits(lowerLimits);
483 },
484 ::py::arg("lowerLimits"))
485 .def(
486 "getForceLowerLimits",
487 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
488 return self->getForceLowerLimits();
489 })
490 .def(
491 "setForceUpperLimit",
492 +[](dart::dynamics::ZeroDofJoint* self,
493 std::size_t _index,
494 double _force) { self->setForceUpperLimit(_index, _force); },
495 ::py::arg("index"),
496 ::py::arg("force"))
497 .def(
498 "getForceUpperLimit",
499 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
500 -> double { return self->getForceUpperLimit(_index); },
501 ::py::arg("index"))
502 .def(
503 "setForceUpperLimits",
504 +[](dart::dynamics::ZeroDofJoint* self,
505 const Eigen::VectorXd& upperLimits) {
506 self->setForceUpperLimits(upperLimits);
507 },
508 ::py::arg("upperLimits"))
509 .def(
510 "getForceUpperLimits",
511 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::VectorXd {
512 return self->getForceUpperLimits();
513 })
514 .def(
515 "setVelocityChange",
516 +[](dart::dynamics::ZeroDofJoint* self,
517 std::size_t _index,
518 double _velocityChange) {
519 self->setVelocityChange(_index, _velocityChange);
520 },
521 ::py::arg("index"),
522 ::py::arg("velocityChange"))
523 .def(
524 "getVelocityChange",
525 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
526 -> double { return self->getVelocityChange(_index); },
527 ::py::arg("index"))
528 .def(
529 "resetVelocityChanges",
530 +[](dart::dynamics::ZeroDofJoint*
531 self) { self->resetVelocityChanges(); })
532 .def(
533 "setConstraintImpulse",
534 +[](dart::dynamics::ZeroDofJoint* self,
535 std::size_t _index,
536 double _impulse) {
537 self->setConstraintImpulse(_index, _impulse);
538 },
539 ::py::arg("index"),
540 ::py::arg("impulse"))
541 .def(
542 "getConstraintImpulse",
543 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
544 -> double { return self->getConstraintImpulse(_index); },
545 ::py::arg("index"))
546 .def(
547 "resetConstraintImpulses",
548 +[](dart::dynamics::ZeroDofJoint*
549 self) { self->resetConstraintImpulses(); })
550 .def(
551 "integratePositions",
552 +[](dart::dynamics::ZeroDofJoint* self, double _dt) {
553 self->integratePositions(_dt);
554 },
555 ::py::arg("dt"))
556 .def(
557 "integrateVelocities",
558 +[](dart::dynamics::ZeroDofJoint* self, double _dt) {
559 self->integrateVelocities(_dt);
560 },
561 ::py::arg("dt"))
562 .def(
563 "getPositionDifferences",
564 +[](const dart::dynamics::ZeroDofJoint* self,
565 const Eigen::VectorXd& _q2,
566 const Eigen::VectorXd& _q1) -> Eigen::VectorXd {
567 return self->getPositionDifferences(_q2, _q1);
568 },
569 ::py::arg("q2"),
570 ::py::arg("q1"))
571 .def(
572 "setSpringStiffness",
573 +[](dart::dynamics::ZeroDofJoint* self,
574 std::size_t _index,
575 double _k) { self->setSpringStiffness(_index, _k); },
576 ::py::arg("index"),
577 ::py::arg("k"))
578 .def(
579 "getSpringStiffness",
580 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
581 -> double { return self->getSpringStiffness(_index); },
582 ::py::arg("index"))
583 .def(
584 "setRestPosition",
585 +[](dart::dynamics::ZeroDofJoint* self,
586 std::size_t _index,
587 double _q0) { self->setRestPosition(_index, _q0); },
588 ::py::arg("index"),
589 ::py::arg("q0"))
590 .def(
591 "getRestPosition",
592 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
593 -> double { return self->getRestPosition(_index); },
594 ::py::arg("index"))
595 .def(
596 "setDampingCoefficient",
597 +[](dart::dynamics::ZeroDofJoint* self,
598 std::size_t _index,
599 double _d) { self->setDampingCoefficient(_index, _d); },
600 ::py::arg("index"),
601 ::py::arg("d"))
602 .def(
603 "getDampingCoefficient",
604 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
605 -> double { return self->getDampingCoefficient(_index); },
606 ::py::arg("index"))
607 .def(
608 "setCoulombFriction",
609 +[](dart::dynamics::ZeroDofJoint* self,
610 std::size_t _index,
611 double _friction) {
612 self->setCoulombFriction(_index, _friction);
613 },
614 ::py::arg("index"),
615 ::py::arg("friction"))
616 .def(
617 "getCoulombFriction",
618 +[](const dart::dynamics::ZeroDofJoint* self, std::size_t _index)
619 -> double { return self->getCoulombFriction(_index); },
620 ::py::arg("index"))
621 .def(
622 "computePotentialEnergy",
623 +[](const dart::dynamics::ZeroDofJoint* self) -> double {
624 return self->computePotentialEnergy();
625 })
626 .def(
627 "getBodyConstraintWrench",
628 +[](const dart::dynamics::ZeroDofJoint* self) -> Eigen::Vector6d {
629 return self->getBodyConstraintWrench();
630 });
631 }
632
633 } // namespace python
634 } // namespace dart
635