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 
37 #include "eigen_geometry_pybind.h"
38 #include "eigen_pybind.h"
39 
40 namespace py = pybind11;
41 
42 namespace dart {
43 namespace python {
44 
Shape(py::module & m)45 void Shape(py::module& m)
46 {
47   auto shape
48       = ::py::class_<
49             dart::dynamics::Shape,
50             dart::common::Subject,
51             std::shared_ptr<dart::dynamics::Shape>>(m, "Shape")
52             .def(
53                 "getType",
54                 +[](const dart::dynamics::Shape* self) -> const std::string& {
55                   return self->getType();
56                 },
57                 ::py::return_value_policy::reference_internal)
58             .def(
59                 "getBoundingBox",
60                 +[](const dart::dynamics::Shape* self)
61                     -> const dart::math::BoundingBox& {
62                   return self->getBoundingBox();
63                 },
64                 ::py::return_value_policy::reference_internal)
65             .def(
66                 "computeInertia",
67                 +[](const dart::dynamics::Shape* self, double mass)
68                     -> Eigen::Matrix3d { return self->computeInertia(mass); },
69                 ::py::arg("mass"))
70             .def(
71                 "computeInertiaFromDensity",
72                 +[](const dart::dynamics::Shape* self,
73                     double density) -> Eigen::Matrix3d {
74                   return self->computeInertiaFromDensity(density);
75                 },
76                 ::py::arg("density"))
77             .def(
78                 "computeInertiaFromMass",
79                 +[](const dart::dynamics::Shape* self,
80                     double mass) -> Eigen::Matrix3d {
81                   return self->computeInertiaFromMass(mass);
82                 },
83                 ::py::arg("mass"))
84             .def(
85                 "getVolume",
86                 +[](const dart::dynamics::Shape* self) -> double {
87                   return self->getVolume();
88                 })
89             .def(
90                 "getID",
91                 +[](const dart::dynamics::Shape* self) -> std::size_t {
92                   return self->getID();
93                 })
94             .def(
95                 "setDataVariance",
96                 +[](dart::dynamics::Shape* self, unsigned int _variance) {
97                   self->setDataVariance(_variance);
98                 },
99                 ::py::arg("variance"))
100             .def(
101                 "addDataVariance",
102                 +[](dart::dynamics::Shape* self, unsigned int _variance) {
103                   self->addDataVariance(_variance);
104                 },
105                 ::py::arg("variance"))
106             .def(
107                 "removeDataVariance",
108                 +[](dart::dynamics::Shape* self, unsigned int _variance) {
109                   self->removeDataVariance(_variance);
110                 },
111                 ::py::arg("variance"))
112             .def(
113                 "getDataVariance",
114                 +[](const dart::dynamics::Shape* self) -> unsigned int {
115                   return self->getDataVariance();
116                 })
117             .def(
118                 "checkDataVariance",
119                 +[](const dart::dynamics::Shape* self,
120                     dart::dynamics::Shape::DataVariance type) -> bool {
121                   return self->checkDataVariance(type);
122                 },
123                 ::py::arg("type"))
124             .def(
125                 "refreshData",
126                 +[](dart::dynamics::Shape* self) { self->refreshData(); })
127             .def(
128                 "notifyAlphaUpdated",
129                 +[](dart::dynamics::Shape* self, double alpha) {
130                   self->notifyAlphaUpdated(alpha);
131                 },
132                 ::py::arg("alpha"))
133             .def(
134                 "notifyColorUpdated",
135                 +[](dart::dynamics::Shape* self, const Eigen::Vector4d& color) {
136                   self->notifyColorUpdated(color);
137                 },
138                 ::py::arg("color"))
139             .def(
140                 "incrementVersion",
141                 +[](dart::dynamics::Shape* self) -> std::size_t {
142                   return self->incrementVersion();
143                 })
144             .def_readonly(
145                 "onVersionChanged", &dart::dynamics::Shape::onVersionChanged);
146 
147 #define DARTPY_DEFINE_SHAPE_TYPE(val)                                          \
148   .value(#val, dart::dynamics::Shape::ShapeType::val)
149 
150   // clang-format off
151   ::py::enum_<dart::dynamics::Shape::ShapeType>(shape, "ShapeType")
152       DARTPY_DEFINE_SHAPE_TYPE(SPHERE)
153       DARTPY_DEFINE_SHAPE_TYPE(BOX)
154       DARTPY_DEFINE_SHAPE_TYPE(ELLIPSOID)
155       DARTPY_DEFINE_SHAPE_TYPE(CYLINDER)
156       DARTPY_DEFINE_SHAPE_TYPE(CAPSULE)
157       DARTPY_DEFINE_SHAPE_TYPE(CONE)
158       DARTPY_DEFINE_SHAPE_TYPE(PLANE)
159       DARTPY_DEFINE_SHAPE_TYPE(MULTISPHERE)
160       DARTPY_DEFINE_SHAPE_TYPE(MESH)
161       DARTPY_DEFINE_SHAPE_TYPE(SOFT_MESH)
162       DARTPY_DEFINE_SHAPE_TYPE(LINE_SEGMENT)
163       DARTPY_DEFINE_SHAPE_TYPE(HEIGHTMAP)
164       DARTPY_DEFINE_SHAPE_TYPE(UNSUPPORTED)
165       .export_values();
166   // clang-format on
167 
168 #define DARTPY_DEFINE_DATA_VARIANCE(val)                                       \
169   .value(#val, dart::dynamics::Shape::DataVariance::val)
170 
171   // clang-format off
172   ::py::enum_<dart::dynamics::Shape::DataVariance>(shape, "DataVariance")
173       DARTPY_DEFINE_DATA_VARIANCE(STATIC           )
174       DARTPY_DEFINE_DATA_VARIANCE(DYNAMIC_TRANSFORM)
175       DARTPY_DEFINE_DATA_VARIANCE(DYNAMIC_PRIMITIVE)
176       DARTPY_DEFINE_DATA_VARIANCE(DYNAMIC_COLOR    )
177       DARTPY_DEFINE_DATA_VARIANCE(DYNAMIC_VERTICES )
178       DARTPY_DEFINE_DATA_VARIANCE(DYNAMIC_ELEMENTS )
179       DARTPY_DEFINE_DATA_VARIANCE(DYNAMIC          )
180       .export_values();
181   // clang-format on
182 
183   ::py::class_<
184       dart::dynamics::BoxShape,
185       dart::dynamics::Shape,
186       std::shared_ptr<dart::dynamics::BoxShape>>(m, "BoxShape")
187       .def(::py::init<const Eigen::Vector3d&>(), ::py::arg("size"))
188       .def(
189           "getType",
190           +[](const dart::dynamics::BoxShape* self) -> const std::string& {
191             return self->getType();
192           },
193           ::py::return_value_policy::reference_internal)
194       .def(
195           "setSize",
196           +[](dart::dynamics::BoxShape* self, const Eigen::Vector3d& _size) {
197             self->setSize(_size);
198           },
199           ::py::arg("size"))
200       .def(
201           "getSize",
202           +[](const dart::dynamics::BoxShape* self) -> const Eigen::Vector3d& {
203             return self->getSize();
204           },
205           ::py::return_value_policy::reference_internal)
206       .def(
207           "computeInertia",
208           +[](const dart::dynamics::BoxShape* self, double mass)
209               -> Eigen::Matrix3d { return self->computeInertia(mass); },
210           ::py::arg("mass"))
211       .def_static(
212           "getStaticType",
213           +[]() -> const std::string& {
214             return dart::dynamics::BoxShape::getStaticType();
215           },
216           ::py::return_value_policy::reference_internal)
217       .def_static(
218           "computeVolume",
219           +[](const Eigen::Vector3d& size) -> double {
220             return dart::dynamics::BoxShape::computeVolume(size);
221           },
222           ::py::arg("size"))
223       .def_static(
224           "computeInertiaOf",
225           +[](const Eigen::Vector3d& size, double mass) -> Eigen::Matrix3d {
226             return dart::dynamics::BoxShape::computeInertia(size, mass);
227           },
228           ::py::arg("size"),
229           ::py::arg("mass"));
230 
231   ::py::class_<
232       dart::dynamics::ConeShape,
233       dart::dynamics::Shape,
234       std::shared_ptr<dart::dynamics::ConeShape>>(m, "ConeShape")
235       .def(
236           ::py::init<double, double>(),
237           ::py::arg("radius"),
238           ::py::arg("height"))
239       .def(
240           "getType",
241           +[](const dart::dynamics::ConeShape* self) -> const std::string& {
242             return self->getType();
243           },
244           ::py::return_value_policy::reference_internal)
245       .def(
246           "getRadius",
247           +[](const dart::dynamics::ConeShape* self) -> double {
248             return self->getRadius();
249           })
250       .def(
251           "setRadius",
252           +[](dart::dynamics::ConeShape* self, double radius) {
253             self->setRadius(radius);
254           },
255           ::py::arg("radius"))
256       .def(
257           "getHeight",
258           +[](const dart::dynamics::ConeShape* self) -> double {
259             return self->getHeight();
260           })
261       .def(
262           "setHeight",
263           +[](dart::dynamics::ConeShape* self, double height) {
264             self->setHeight(height);
265           },
266           ::py::arg("height"))
267       .def(
268           "computeInertia",
269           +[](const dart::dynamics::ConeShape* self, double mass)
270               -> Eigen::Matrix3d { return self->computeInertia(mass); },
271           ::py::arg("mass"))
272       .def_static(
273           "getStaticType",
274           +[]() -> const std::string& {
275             return dart::dynamics::ConeShape::getStaticType();
276           },
277           ::py::return_value_policy::reference_internal)
278       .def_static(
279           "computeVolume",
280           +[](double radius, double height) -> double {
281             return dart::dynamics::ConeShape::computeVolume(radius, height);
282           },
283           ::py::arg("radius"),
284           ::py::arg("height"))
285       .def_static(
286           "computeInertiaOf",
287           +[](double radius, double height, double mass) -> Eigen::Matrix3d {
288             return dart::dynamics::ConeShape::computeInertia(
289                 radius, height, mass);
290           },
291           ::py::arg("radius"),
292           ::py::arg("height"),
293           ::py::arg("mass"));
294 
295   ::py::class_<
296       dart::dynamics::MeshShape,
297       dart::dynamics::Shape,
298       std::shared_ptr<dart::dynamics::MeshShape>>(m, "MeshShape")
299       .def(
300           ::py::init<const Eigen::Vector3d&, const aiScene*>(),
301           ::py::arg("scale"),
302           ::py::arg("mesh"))
303       .def(
304           ::py::init<
305               const Eigen::Vector3d&,
306               const aiScene*,
307               const dart::common::Uri&>(),
308           ::py::arg("scale"),
309           ::py::arg("mesh"),
310           ::py::arg("uri"))
311       .def(
312           ::py::init<
313               const Eigen::Vector3d&,
314               const aiScene*,
315               const dart::common::Uri&,
316               dart::common::ResourceRetrieverPtr>(),
317           ::py::arg("scale"),
318           ::py::arg("mesh"),
319           ::py::arg("uri"),
320           ::py::arg("resourceRetriever"))
321       .def(
322           "getType",
323           +[](const dart::dynamics::MeshShape* self) -> const std::string& {
324             return self->getType();
325           },
326           ::py::return_value_policy::reference_internal)
327       .def("update", +[](dart::dynamics::MeshShape* self) { self->update(); })
328       .def(
329           "notifyAlphaUpdated",
330           +[](dart::dynamics::MeshShape* self, double alpha) {
331             self->notifyAlphaUpdated(alpha);
332           },
333           ::py::arg("alpha"))
334       .def(
335           "setMesh",
336           +[](dart::dynamics::MeshShape* self, const aiScene* mesh) {
337             self->setMesh(mesh);
338           },
339           ::py::arg("mesh"))
340       .def(
341           "setMesh",
342           +[](dart::dynamics::MeshShape* self,
343               const aiScene* mesh,
344               const std::string& path) { self->setMesh(mesh, path); },
345           ::py::arg("mesh"),
346           ::py::arg("path"))
347       .def(
348           "setMesh",
349           +[](dart::dynamics::MeshShape* self,
350               const aiScene* mesh,
351               const std::string& path,
352               dart::common::ResourceRetrieverPtr resourceRetriever) {
353             self->setMesh(mesh, path, resourceRetriever);
354           },
355           ::py::arg("mesh"),
356           ::py::arg("path"),
357           ::py::arg("resourceRetriever"))
358       .def(
359           "setMesh",
360           +[](dart::dynamics::MeshShape* self,
361               const aiScene* mesh,
362               const dart::common::Uri& path) { self->setMesh(mesh, path); },
363           ::py::arg("mesh"),
364           ::py::arg("path"))
365       .def(
366           "setMesh",
367           +[](dart::dynamics::MeshShape* self,
368               const aiScene* mesh,
369               const dart::common::Uri& path,
370               dart::common::ResourceRetrieverPtr resourceRetriever) {
371             self->setMesh(mesh, path, resourceRetriever);
372           },
373           ::py::arg("mesh"),
374           ::py::arg("path"),
375           ::py::arg("resourceRetriever"))
376       .def(
377           "getMeshUri",
378           +[](const dart::dynamics::MeshShape* self) -> std::string {
379             return self->getMeshUri();
380           })
381       .def(
382           "getMeshUri2",
383           +[](const dart::dynamics::MeshShape* self)
384               -> const dart::common::Uri& { return self->getMeshUri2(); },
385           ::py::return_value_policy::reference_internal)
386       .def(
387           "getMeshPath",
388           +[](const dart::dynamics::MeshShape* self) -> const std::string& {
389             return self->getMeshPath();
390           },
391           ::py::return_value_policy::reference_internal)
392       .def(
393           "getResourceRetriever",
394           +[](dart::dynamics::MeshShape* self)
395               -> dart::common::ResourceRetrieverPtr {
396             return self->getResourceRetriever();
397           })
398       .def(
399           "setScale",
400           +[](dart::dynamics::MeshShape* self, const Eigen::Vector3d& scale) {
401             self->setScale(scale);
402           },
403           ::py::arg("scale"))
404       .def(
405           "getScale",
406           +[](const dart::dynamics::MeshShape* self) -> const Eigen::Vector3d& {
407             return self->getScale();
408           },
409           ::py::return_value_policy::reference_internal)
410       .def(
411           "setColorMode",
412           +[](dart::dynamics::MeshShape* self,
413               dart::dynamics::MeshShape::ColorMode mode) {
414             self->setColorMode(mode);
415           },
416           ::py::arg("mode"))
417       .def(
418           "getColorMode",
419           +[](const dart::dynamics::MeshShape* self)
420               -> dart::dynamics::MeshShape::ColorMode {
421             return self->getColorMode();
422           })
423       .def(
424           "setColorIndex",
425           +[](dart::dynamics::MeshShape* self, int index) {
426             self->setColorIndex(index);
427           },
428           ::py::arg("index"))
429       .def(
430           "getColorIndex",
431           +[](const dart::dynamics::MeshShape* self) -> int {
432             return self->getColorIndex();
433           })
434       .def(
435           "getDisplayList",
436           +[](const dart::dynamics::MeshShape* self) -> int {
437             return self->getDisplayList();
438           })
439       .def(
440           "setDisplayList",
441           +[](dart::dynamics::MeshShape* self, int index) {
442             self->setDisplayList(index);
443           },
444           ::py::arg("index"))
445       .def(
446           "computeInertia",
447           +[](const dart::dynamics::MeshShape* self, double mass)
448               -> Eigen::Matrix3d { return self->computeInertia(mass); },
449           ::py::arg("mass"))
450       .def_static(
451           "getStaticType",
452           +[]() -> const std::string& {
453             return dart::dynamics::MeshShape::getStaticType();
454           },
455           ::py::return_value_policy::reference_internal);
456 
457   auto attr = m.attr("MeshShape");
458 
459   ::py::enum_<dart::dynamics::MeshShape::ColorMode>(attr, "ColorMode")
460       .value(
461           "MATERIAL_COLOR",
462           dart::dynamics::MeshShape::ColorMode::MATERIAL_COLOR)
463       .value("COLOR_INDEX", dart::dynamics::MeshShape::ColorMode::COLOR_INDEX)
464       .value("SHAPE_COLOR", dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR)
465       .export_values();
466 
467   ::py::class_<
468       dart::dynamics::ArrowShape,
469       dart::dynamics::MeshShape,
470       std::shared_ptr<dart::dynamics::ArrowShape>>(m, "ArrowShape")
471       .def(
472           ::py::init<const Eigen::Vector3d&, const Eigen::Vector3d&>(),
473           ::py::arg("tail"),
474           ::py::arg("head"))
475       .def(
476           ::py::init<
477               const Eigen::Vector3d&,
478               const Eigen::Vector3d&,
479               const dart::dynamics::ArrowShape::Properties&>(),
480           ::py::arg("tail"),
481           ::py::arg("head"),
482           ::py::arg("properties"))
483       .def(
484           ::py::init<
485               const Eigen::Vector3d&,
486               const Eigen::Vector3d&,
487               const dart::dynamics::ArrowShape::Properties&,
488               const Eigen::Vector4d&>(),
489           ::py::arg("tail"),
490           ::py::arg("head"),
491           ::py::arg("properties"),
492           ::py::arg("color"))
493       .def(
494           ::py::init<
495               const Eigen::Vector3d&,
496               const Eigen::Vector3d&,
497               const dart::dynamics::ArrowShape::Properties&,
498               const Eigen::Vector4d&,
499               std::size_t>(),
500           ::py::arg("tail"),
501           ::py::arg("head"),
502           ::py::arg("properties"),
503           ::py::arg("color"),
504           ::py::arg("resolution"))
505       .def(
506           "setPositions",
507           +[](dart::dynamics::ArrowShape* self,
508               const Eigen::Vector3d& _tail,
509               const Eigen::Vector3d& _head) {
510             self->setPositions(_tail, _head);
511           },
512           ::py::arg("tail"),
513           ::py::arg("head"))
514       .def(
515           "getTail",
516           +[](const dart::dynamics::ArrowShape* self)
517               -> const Eigen::Vector3d& { return self->getTail(); },
518           ::py::return_value_policy::reference_internal)
519       .def(
520           "getHead",
521           +[](const dart::dynamics::ArrowShape* self)
522               -> const Eigen::Vector3d& { return self->getHead(); },
523           ::py::return_value_policy::reference_internal)
524       .def(
525           "setProperties",
526           +[](dart::dynamics::ArrowShape* self,
527               const dart::dynamics::ArrowShape::Properties& _properties) {
528             self->setProperties(_properties);
529           },
530           ::py::arg("properties"))
531       .def(
532           "notifyColorUpdated",
533           +[](dart::dynamics::ArrowShape* self, const Eigen::Vector4d& _color) {
534             self->notifyColorUpdated(_color);
535           },
536           ::py::arg("color"))
537       .def(
538           "getProperties",
539           +[](const dart::dynamics::ArrowShape* self)
540               -> const dart::dynamics::ArrowShape::Properties& {
541             return self->getProperties();
542           },
543           ::py::return_value_policy::reference_internal)
544       .def(
545           "configureArrow",
546           +[](dart::dynamics::ArrowShape* self,
547               const Eigen::Vector3d& _tail,
548               const Eigen::Vector3d& _head,
549               const dart::dynamics::ArrowShape::Properties& _properties) {
550             self->configureArrow(_tail, _head, _properties);
551           },
552           ::py::arg("tail"),
553           ::py::arg("head"),
554           ::py::arg("properties"));
555 
556   ::py::class_<dart::dynamics::ArrowShape::Properties>(
557       m, "ArrowShapeProperties")
558       .def(::py::init<>())
559       .def(::py::init<double>(), ::py::arg("radius"))
560       .def(
561           ::py::init<double, double>(),
562           ::py::arg("radius"),
563           ::py::arg("headRadiusScale"))
564       .def(
565           ::py::init<double, double, double>(),
566           ::py::arg("radius"),
567           ::py::arg("headRadiusScale"),
568           ::py::arg("headLengthScale"))
569       .def(
570           ::py::init<double, double, double, double>(),
571           ::py::arg("radius"),
572           ::py::arg("headRadiusScale"),
573           ::py::arg("headLengthScale"),
574           ::py::arg("minHeadLength"))
575       .def(
576           ::py::init<double, double, double, double, double>(),
577           ::py::arg("radius"),
578           ::py::arg("headRadiusScale"),
579           ::py::arg("headLengthScale"),
580           ::py::arg("minHeadLength"),
581           ::py::arg("maxHeadLength"))
582       .def(
583           ::py::init<double, double, double, double, double, bool>(),
584           ::py::arg("radius"),
585           ::py::arg("headRadiusScale"),
586           ::py::arg("headLengthScale"),
587           ::py::arg("minHeadLength"),
588           ::py::arg("maxHeadLength"),
589           ::py::arg("doubleArrow"))
590       .def_readwrite(
591           "mRadius", &dart::dynamics::ArrowShape::Properties::mRadius)
592       .def_readwrite(
593           "mHeadRadiusScale",
594           &dart::dynamics::ArrowShape::Properties::mHeadRadiusScale)
595       .def_readwrite(
596           "mHeadLengthScale",
597           &dart::dynamics::ArrowShape::Properties::mHeadLengthScale)
598       .def_readwrite(
599           "mMinHeadLength",
600           &dart::dynamics::ArrowShape::Properties::mMinHeadLength)
601       .def_readwrite(
602           "mMaxHeadLength",
603           &dart::dynamics::ArrowShape::Properties::mMaxHeadLength)
604       .def_readwrite(
605           "mDoubleArrow",
606           &dart::dynamics::ArrowShape::Properties::mDoubleArrow);
607 
608   ::py::class_<
609       dart::dynamics::PlaneShape,
610       dart::dynamics::Shape,
611       std::shared_ptr<dart::dynamics::PlaneShape>>(m, "PlaneShape")
612       .def(
613           ::py::init<const Eigen::Vector3d&, double>(),
614           ::py::arg("normal"),
615           ::py::arg("offset"))
616       .def(
617           ::py::init<const Eigen::Vector3d&, const Eigen::Vector3d&>(),
618           ::py::arg("normal"),
619           ::py::arg("point"))
620       .def(
621           "getType",
622           +[](const dart::dynamics::PlaneShape* self) -> const std::string& {
623             return self->getType();
624           },
625           ::py::return_value_policy::reference_internal)
626       .def(
627           "computeInertia",
628           +[](const dart::dynamics::PlaneShape* self, double mass)
629               -> Eigen::Matrix3d { return self->computeInertia(mass); },
630           ::py::arg("mass"))
631       .def(
632           "setNormal",
633           +[](dart::dynamics::PlaneShape* self,
634               const Eigen::Vector3d& _normal) { self->setNormal(_normal); },
635           ::py::arg("normal"))
636       .def(
637           "getNormal",
638           +[](const dart::dynamics::PlaneShape* self)
639               -> const Eigen::Vector3d& { return self->getNormal(); },
640           ::py::return_value_policy::reference_internal)
641       .def(
642           "setOffset",
643           +[](dart::dynamics::PlaneShape* self, double _offset) {
644             self->setOffset(_offset);
645           },
646           ::py::arg("offset"))
647       .def(
648           "getOffset",
649           +[](const dart::dynamics::PlaneShape* self) -> double {
650             return self->getOffset();
651           })
652       .def(
653           "setNormalAndOffset",
654           +[](dart::dynamics::PlaneShape* self,
655               const Eigen::Vector3d& _normal,
656               double _offset) { self->setNormalAndOffset(_normal, _offset); },
657           ::py::arg("normal"),
658           ::py::arg("offset"))
659       .def(
660           "setNormalAndPoint",
661           +[](dart::dynamics::PlaneShape* self,
662               const Eigen::Vector3d& _normal,
663               const Eigen::Vector3d& _point) {
664             self->setNormalAndPoint(_normal, _point);
665           },
666           ::py::arg("normal"),
667           ::py::arg("point"))
668       .def(
669           "computeDistance",
670           +[](const dart::dynamics::PlaneShape* self,
671               const Eigen::Vector3d& _point) -> double {
672             return self->computeDistance(_point);
673           },
674           ::py::arg("point"))
675       .def(
676           "computeSignedDistance",
677           +[](const dart::dynamics::PlaneShape* self,
678               const Eigen::Vector3d& _point) -> double {
679             return self->computeSignedDistance(_point);
680           },
681           ::py::arg("point"))
682       .def_static(
683           "getStaticType",
684           +[]() -> const std::string& {
685             return dart::dynamics::PlaneShape::getStaticType();
686           },
687           ::py::return_value_policy::reference_internal);
688   ::py::class_<
689       dart::dynamics::PointCloudShape,
690       dart::dynamics::Shape,
691       std::shared_ptr<dart::dynamics::PointCloudShape>>
692       pointCloudShape(m, "PointCloudShape");
693 
694   pointCloudShape.def(::py::init<double>(), ::py::arg("visualSize") = 0.01)
695       .def(
696           "getType",
697           +[](const dart::dynamics::PointCloudShape* self)
698               -> const std::string& { return self->getType(); },
699           ::py::return_value_policy::reference_internal)
700       .def(
701           "computeInertia",
702           +[](const dart::dynamics::PointCloudShape* self, double mass)
703               -> Eigen::Matrix3d { return self->computeInertia(mass); },
704           ::py::arg("mass"))
705       .def(
706           "reserve",
707           +[](dart::dynamics::PointCloudShape* self, std::size_t size) -> void {
708             return self->reserve(size);
709           },
710           ::py::arg("size"))
711       .def(
712           "addPoint",
713           +[](dart::dynamics::PointCloudShape* self,
714               const Eigen::Vector3d& point) -> void {
715             return self->addPoint(point);
716           },
717           ::py::arg("point"))
718       .def(
719           "addPoint",
720           +[](dart::dynamics::PointCloudShape* self,
721               const std::vector<Eigen::Vector3d>& points) -> void {
722             return self->addPoint(points);
723           },
724           ::py::arg("points"))
725       .def(
726           "setPoint",
727           +[](dart::dynamics::PointCloudShape* self,
728               const std::vector<Eigen::Vector3d>& points) -> void {
729             return self->setPoint(points);
730           },
731           ::py::arg("points"))
732       .def(
733           "getPoints",
734           +[](const dart::dynamics::PointCloudShape* self)
735               -> const std::vector<Eigen::Vector3d>& {
736             return self->getPoints();
737           },
738           ::py::return_value_policy::reference_internal)
739       .def(
740           "getNumPoints",
741           +[](const dart::dynamics::PointCloudShape* self) -> std::size_t {
742             return self->getNumPoints();
743           })
744       .def(
745           "removeAllPoints",
746           +[](dart::dynamics::PointCloudShape* self) -> void {
747             return self->removeAllPoints();
748           })
749       .def(
750           "setPointShapeType",
751           +[](dart::dynamics::PointCloudShape* self,
752               dart::dynamics::PointCloudShape::PointShapeType type) -> void {
753             return self->setPointShapeType(type);
754           },
755           ::py::arg("type"))
756       .def(
757           "getPointShapeType",
758           +[](const dart::dynamics::PointCloudShape* self)
759               -> dart::dynamics::PointCloudShape::PointShapeType {
760             return self->getPointShapeType();
761           })
762       .def(
763           "setColorMode",
764           +[](dart::dynamics::PointCloudShape* self,
765               dart::dynamics::PointCloudShape::ColorMode mode) -> void {
766             return self->setColorMode(mode);
767           },
768           ::py::arg("mode"))
769       .def(
770           "getColorMode",
771           +[](const dart::dynamics::PointCloudShape* self)
772               -> dart::dynamics::PointCloudShape::ColorMode {
773             return self->getColorMode();
774           })
775       .def(
776           "setOverallColor",
777           +[](dart::dynamics::PointCloudShape* self,
778               const Eigen::Vector4d& color) -> void {
779             return self->setOverallColor(color);
780           },
781           ::py::arg("color"))
782       .def(
783           "getOverallColor",
784           +[](const dart::dynamics::PointCloudShape* self) -> Eigen::Vector4d {
785             return self->getOverallColor();
786           })
787       .def(
788           "setColors",
789           +[](dart::dynamics::PointCloudShape* self,
790               const std::vector<
791                   Eigen::Vector4d,
792                   Eigen::aligned_allocator<Eigen::Vector4d>>& colors) -> void {
793             return self->setColors(colors);
794           },
795           ::py::arg("colors"))
796       .def(
797           "getColors",
798           +[](const dart::dynamics::PointCloudShape* self)
799               -> const std::vector<
800                   Eigen::Vector4d,
801                   Eigen::aligned_allocator<Eigen::Vector4d>>& {
802             return self->getColors();
803           })
804       .def(
805           "setVisualSize",
806           +[](dart::dynamics::PointCloudShape* self, double size) -> void {
807             return self->setVisualSize(size);
808           },
809           ::py::arg("size"))
810       .def(
811           "getVisualSize",
812           +[](const dart::dynamics::PointCloudShape* self) -> double {
813             return self->getVisualSize();
814           })
815       .def(
816           "notifyColorUpdated",
817           +[](dart::dynamics::PointCloudShape* self,
818               const Eigen::Vector4d& color) {
819             self->notifyColorUpdated(color);
820           },
821           ::py::arg("color"));
822 
823   ::py::enum_<dart::dynamics::PointCloudShape::ColorMode>(
824       pointCloudShape, "ColorMode")
825       .value(
826           "USE_SHAPE_COLOR",
827           dart::dynamics::PointCloudShape::ColorMode::USE_SHAPE_COLOR)
828       .value(
829           "BIND_OVERALL",
830           dart::dynamics::PointCloudShape::ColorMode::BIND_OVERALL)
831       .value(
832           "BIND_PER_POINT",
833           dart::dynamics::PointCloudShape::ColorMode::BIND_PER_POINT)
834       .export_values();
835 
836   ::py::enum_<dart::dynamics::PointCloudShape::PointShapeType>(
837       pointCloudShape, "PointShapeType")
838       .value("BOX", dart::dynamics::PointCloudShape::PointShapeType::BOX)
839       .value(
840           "BILLBOARD_SQUARE",
841           dart::dynamics::PointCloudShape::PointShapeType::BILLBOARD_SQUARE)
842       .value(
843           "BILLBOARD_CIRCLE",
844           dart::dynamics::PointCloudShape::PointShapeType::BILLBOARD_CIRCLE)
845       .export_values();
846 
847   ::py::class_<
848       dart::dynamics::SphereShape,
849       dart::dynamics::Shape,
850       std::shared_ptr<dart::dynamics::SphereShape>>(m, "SphereShape")
851       .def(::py::init<double>(), ::py::arg("radius"))
852       .def(
853           "getType",
854           +[](const dart::dynamics::SphereShape* self) -> const std::string& {
855             return self->getType();
856           },
857           ::py::return_value_policy::reference_internal)
858       .def(
859           "setRadius",
860           +[](dart::dynamics::SphereShape* self, double radius) {
861             self->setRadius(radius);
862           },
863           ::py::arg("radius"))
864       .def(
865           "getRadius",
866           +[](const dart::dynamics::SphereShape* self) -> double {
867             return self->getRadius();
868           })
869       .def(
870           "computeInertia",
871           +[](const dart::dynamics::SphereShape* self, double mass)
872               -> Eigen::Matrix3d { return self->computeInertia(mass); },
873           ::py::arg("mass"))
874       .def_static(
875           "getStaticType",
876           +[]() -> const std::string& {
877             return dart::dynamics::SphereShape::getStaticType();
878           },
879           ::py::return_value_policy::reference_internal)
880       .def_static(
881           "computeVolumeOf",
882           +[](double radius) -> double {
883             return dart::dynamics::SphereShape::computeVolume(radius);
884           },
885           ::py::arg("radius"))
886       .def_static(
887           "computeInertiaOf",
888           +[](double radius, double mass) -> Eigen::Matrix3d {
889             return dart::dynamics::SphereShape::computeInertia(radius, mass);
890           },
891           ::py::arg("radius"),
892           ::py::arg("mass"));
893 
894   ::py::class_<
895       dart::dynamics::CapsuleShape,
896       dart::dynamics::Shape,
897       std::shared_ptr<dart::dynamics::CapsuleShape>>(m, "CapsuleShape")
898       .def(
899           ::py::init<double, double>(),
900           ::py::arg("radius"),
901           ::py::arg("height"))
902       .def(
903           "getType",
904           +[](const dart::dynamics::CapsuleShape* self) -> const std::string& {
905             return self->getType();
906           },
907           ::py::return_value_policy::reference_internal)
908       .def(
909           "getRadius",
910           +[](const dart::dynamics::CapsuleShape* self) -> double {
911             return self->getRadius();
912           })
913       .def(
914           "setRadius",
915           +[](dart::dynamics::CapsuleShape* self, double radius) {
916             self->setRadius(radius);
917           },
918           ::py::arg("radius"))
919       .def(
920           "getHeight",
921           +[](const dart::dynamics::CapsuleShape* self) -> double {
922             return self->getHeight();
923           })
924       .def(
925           "setHeight",
926           +[](dart::dynamics::CapsuleShape* self, double height) {
927             self->setHeight(height);
928           },
929           ::py::arg("height"))
930       .def(
931           "computeInertia",
932           +[](const dart::dynamics::CapsuleShape* self, double mass)
933               -> Eigen::Matrix3d { return self->computeInertia(mass); },
934           ::py::arg("mass"))
935       .def_static(
936           "getStaticType",
937           +[]() -> const std::string& {
938             return dart::dynamics::CapsuleShape::getStaticType();
939           },
940           ::py::return_value_policy::reference_internal)
941       .def_static(
942           "computeVolumeOf",
943           +[](double radius, double height) -> double {
944             return dart::dynamics::CapsuleShape::computeVolume(radius, height);
945           },
946           ::py::arg("radius"),
947           ::py::arg("height"))
948       .def_static(
949           "computeInertiaOf",
950           +[](double radius, double height, double mass) -> Eigen::Matrix3d {
951             return dart::dynamics::CapsuleShape::computeInertia(
952                 radius, height, mass);
953           },
954           ::py::arg("radius"),
955           ::py::arg("height"),
956           ::py::arg("mass"));
957 
958   ::py::class_<
959       dart::dynamics::CylinderShape,
960       dart::dynamics::Shape,
961       std::shared_ptr<dart::dynamics::CylinderShape>>(m, "CylinderShape")
962       .def(
963           ::py::init<double, double>(),
964           ::py::arg("radius"),
965           ::py::arg("height"))
966       .def(
967           "getType",
968           +[](const dart::dynamics::CylinderShape* self) -> const std::string& {
969             return self->getType();
970           },
971           ::py::return_value_policy::reference_internal)
972       .def(
973           "getRadius",
974           +[](const dart::dynamics::CylinderShape* self) -> double {
975             return self->getRadius();
976           })
977       .def(
978           "setRadius",
979           +[](dart::dynamics::CylinderShape* self, double _radius) {
980             self->setRadius(_radius);
981           },
982           ::py::arg("radius"))
983       .def(
984           "getHeight",
985           +[](const dart::dynamics::CylinderShape* self) -> double {
986             return self->getHeight();
987           })
988       .def(
989           "setHeight",
990           +[](dart::dynamics::CylinderShape* self, double _height) {
991             self->setHeight(_height);
992           },
993           ::py::arg("height"))
994       .def(
995           "computeInertia",
996           +[](const dart::dynamics::CylinderShape* self, double mass)
997               -> Eigen::Matrix3d { return self->computeInertia(mass); },
998           ::py::arg("mass"))
999       .def_static(
1000           "getStaticType",
1001           +[]() -> const std::string& {
1002             return dart::dynamics::CylinderShape::getStaticType();
1003           },
1004           ::py::return_value_policy::reference_internal)
1005       .def_static(
1006           "computeVolumeOf",
1007           +[](double radius, double height) -> double {
1008             return dart::dynamics::CylinderShape::computeVolume(radius, height);
1009           },
1010           ::py::arg("radius"),
1011           ::py::arg("height"))
1012       .def_static(
1013           "computeInertiaOf",
1014           +[](double radius, double height, double mass) -> Eigen::Matrix3d {
1015             return dart::dynamics::CylinderShape::computeInertia(
1016                 radius, height, mass);
1017           },
1018           ::py::arg("radius"),
1019           ::py::arg("height"),
1020           ::py::arg("mass"));
1021 
1022   ::py::class_<
1023       dart::dynamics::SoftMeshShape,
1024       dart::dynamics::Shape,
1025       std::shared_ptr<dart::dynamics::SoftMeshShape>>(m, "SoftMeshShape")
1026       .def(
1027           ::py::init<dart::dynamics::SoftBodyNode*>(),
1028           ::py::arg("softBodyNode"))
1029       .def(
1030           "getType",
1031           +[](const dart::dynamics::SoftMeshShape* self) -> const std::string& {
1032             return self->getType();
1033           },
1034           ::py::return_value_policy::reference_internal)
1035       .def(
1036           "update",
1037           +[](dart::dynamics::SoftMeshShape* self) { self->update(); })
1038       .def(
1039           "computeInertia",
1040           +[](const dart::dynamics::SoftMeshShape* self, double mass)
1041               -> Eigen::Matrix3d { return self->computeInertia(mass); },
1042           ::py::arg("mass"))
1043       .def_static(
1044           "getStaticType",
1045           +[]() -> const std::string& {
1046             return dart::dynamics::SoftMeshShape::getStaticType();
1047           },
1048           ::py::return_value_policy::reference_internal);
1049 
1050   ::py::class_<
1051       dart::dynamics::EllipsoidShape,
1052       dart::dynamics::Shape,
1053       std::shared_ptr<dart::dynamics::EllipsoidShape>>(m, "EllipsoidShape")
1054       .def(::py::init<const Eigen::Vector3d&>(), ::py::arg("diameters"))
1055       .def(
1056           "getType",
1057           +[](const dart::dynamics::EllipsoidShape* self)
1058               -> const std::string& { return self->getType(); },
1059           ::py::return_value_policy::reference_internal)
1060       .def(
1061           "setDiameters",
1062           +[](dart::dynamics::EllipsoidShape* self,
1063               const Eigen::Vector3d& diameters) {
1064             self->setDiameters(diameters);
1065           },
1066           ::py::arg("diameters"))
1067       .def(
1068           "getDiameters",
1069           +[](const dart::dynamics::EllipsoidShape* self)
1070               -> const Eigen::Vector3d& { return self->getDiameters(); },
1071           ::py::return_value_policy::reference_internal)
1072       .def(
1073           "setRadii",
1074           +[](dart::dynamics::EllipsoidShape* self,
1075               const Eigen::Vector3d& radii) { self->setRadii(radii); },
1076           ::py::arg("radii"))
1077       .def(
1078           "getRadii",
1079           +[](const dart::dynamics::EllipsoidShape* self)
1080               -> const Eigen::Vector3d { return self->getRadii(); })
1081       .def(
1082           "computeInertia",
1083           +[](const dart::dynamics::EllipsoidShape* self, double mass)
1084               -> Eigen::Matrix3d { return self->computeInertia(mass); },
1085           ::py::arg("mass"))
1086       .def(
1087           "isSphere",
1088           +[](const dart::dynamics::EllipsoidShape* self) -> bool {
1089             return self->isSphere();
1090           })
1091       .def_static(
1092           "getStaticType",
1093           +[]() -> const std::string& {
1094             return dart::dynamics::EllipsoidShape::getStaticType();
1095           },
1096           ::py::return_value_policy::reference_internal)
1097       .def_static(
1098           "computeVolumeOf",
1099           +[](const Eigen::Vector3d& diameters) -> double {
1100             return dart::dynamics::EllipsoidShape::computeVolume(diameters);
1101           },
1102           ::py::arg("diameters"))
1103       .def_static(
1104           "computeInertiaOf",
1105           +[](const Eigen::Vector3d& diameters,
1106               double mass) -> Eigen::Matrix3d {
1107             return dart::dynamics::EllipsoidShape::computeInertia(
1108                 diameters, mass);
1109           },
1110           ::py::arg("diameters"),
1111           ::py::arg("mass"));
1112 
1113   ::py::class_<
1114       dart::dynamics::LineSegmentShape,
1115       dart::dynamics::Shape,
1116       std::shared_ptr<dart::dynamics::LineSegmentShape>>(m, "LineSegmentShape")
1117       .def(::py::init<>())
1118       .def(::py::init<float>(), ::py::arg("thickness"))
1119       .def(
1120           ::py::init<const Eigen::Vector3d&, const Eigen::Vector3d&>(),
1121           ::py::arg("v1"),
1122           ::py::arg("v2"))
1123       .def(
1124           ::py::init<const Eigen::Vector3d&, const Eigen::Vector3d&, float>(),
1125           ::py::arg("v1"),
1126           ::py::arg("v2"),
1127           ::py::arg("thickness"))
1128       .def(
1129           "getType",
1130           +[](const dart::dynamics::LineSegmentShape* self)
1131               -> const std::string& { return self->getType(); },
1132           ::py::return_value_policy::reference_internal)
1133       .def(
1134           "setThickness",
1135           +[](dart::dynamics::LineSegmentShape* self, float _thickness) {
1136             self->setThickness(_thickness);
1137           },
1138           ::py::arg("thickness"))
1139       .def(
1140           "getThickness",
1141           +[](const dart::dynamics::LineSegmentShape* self) -> float {
1142             return self->getThickness();
1143           })
1144       .def(
1145           "addVertex",
1146           +[](dart::dynamics::LineSegmentShape* self, const Eigen::Vector3d& _v)
1147               -> std::size_t { return self->addVertex(_v); },
1148           ::py::arg("v"))
1149       .def(
1150           "addVertex",
1151           +[](dart::dynamics::LineSegmentShape* self,
1152               const Eigen::Vector3d& _v,
1153               std::size_t _parent) -> std::size_t {
1154             return self->addVertex(_v, _parent);
1155           },
1156           ::py::arg("v"),
1157           ::py::arg("parent"))
1158       .def(
1159           "removeVertex",
1160           +[](dart::dynamics::LineSegmentShape* self, std::size_t _idx) {
1161             self->removeVertex(_idx);
1162           },
1163           ::py::arg("idx"))
1164       .def(
1165           "setVertex",
1166           +[](dart::dynamics::LineSegmentShape* self,
1167               std::size_t _idx,
1168               const Eigen::Vector3d& _v) { self->setVertex(_idx, _v); },
1169           ::py::arg("idx"),
1170           ::py::arg("v"))
1171       .def(
1172           "getVertex",
1173           +[](const dart::dynamics::LineSegmentShape* self, std::size_t _idx)
1174               -> const Eigen::Vector3d& { return self->getVertex(_idx); },
1175           ::py::return_value_policy::reference_internal,
1176           ::py::arg("idx"))
1177       .def(
1178           "addConnection",
1179           +[](dart::dynamics::LineSegmentShape* self,
1180               std::size_t _idx1,
1181               std::size_t _idx2) { self->addConnection(_idx1, _idx2); },
1182           ::py::arg("idx1"),
1183           ::py::arg("idx2"))
1184       .def(
1185           "removeConnection",
1186           +[](dart::dynamics::LineSegmentShape* self,
1187               std::size_t _vertexIdx1,
1188               std::size_t _vertexIdx2) {
1189             self->removeConnection(_vertexIdx1, _vertexIdx2);
1190           },
1191           ::py::arg("vertexIdx1"),
1192           ::py::arg("vertexIdx2"))
1193       .def(
1194           "removeConnection",
1195           +[](dart::dynamics::LineSegmentShape* self,
1196               std::size_t _connectionIdx) {
1197             self->removeConnection(_connectionIdx);
1198           },
1199           ::py::arg("connectionIdx"))
1200       .def(
1201           "computeInertia",
1202           +[](const dart::dynamics::LineSegmentShape* self, double mass)
1203               -> Eigen::Matrix3d { return self->computeInertia(mass); },
1204           ::py::arg("mass"))
1205       .def_static(
1206           "getStaticType",
1207           +[]() -> const std::string& {
1208             return dart::dynamics::LineSegmentShape::getStaticType();
1209           },
1210           ::py::return_value_policy::reference_internal);
1211 
1212   ::py::class_<
1213       dart::dynamics::MultiSphereConvexHullShape,
1214       dart::dynamics::Shape,
1215       std::shared_ptr<dart::dynamics::MultiSphereConvexHullShape>>(
1216       m, "MultiSphereConvexHullShape")
1217       .def(
1218           ::py::init<
1219               const dart::dynamics::MultiSphereConvexHullShape::Spheres&>(),
1220           ::py::arg("spheres"))
1221       .def(
1222           "getType",
1223           +[](const dart::dynamics::MultiSphereConvexHullShape* self)
1224               -> const std::string& { return self->getType(); },
1225           ::py::return_value_policy::reference_internal)
1226       .def(
1227           "addSpheres",
1228           +[](dart::dynamics::MultiSphereConvexHullShape* self,
1229               const dart::dynamics::MultiSphereConvexHullShape::Spheres&
1230                   spheres) { self->addSpheres(spheres); },
1231           ::py::arg("spheres"))
1232       .def(
1233           "addSphere",
1234           +[](dart::dynamics::MultiSphereConvexHullShape* self,
1235               const dart::dynamics::MultiSphereConvexHullShape::Sphere&
1236                   sphere) { self->addSphere(sphere); },
1237           ::py::arg("sphere"))
1238       .def(
1239           "addSphere",
1240           +[](dart::dynamics::MultiSphereConvexHullShape* self,
1241               double radius,
1242               const Eigen::Vector3d& position) {
1243             self->addSphere(radius, position);
1244           },
1245           ::py::arg("radius"),
1246           ::py::arg("position"))
1247       .def(
1248           "removeAllSpheres",
1249           +[](dart::dynamics::MultiSphereConvexHullShape* self) {
1250             self->removeAllSpheres();
1251           })
1252       .def(
1253           "getNumSpheres",
1254           +[](const dart::dynamics::MultiSphereConvexHullShape* self)
1255               -> std::size_t { return self->getNumSpheres(); })
1256       .def(
1257           "computeInertia",
1258           +[](const dart::dynamics::MultiSphereConvexHullShape* self,
1259               double mass) -> Eigen::Matrix3d {
1260             return self->computeInertia(mass);
1261           },
1262           ::py::arg("mass"))
1263       .def_static(
1264           "getStaticType",
1265           +[]() -> const std::string& {
1266             return dart::dynamics::MultiSphereConvexHullShape::getStaticType();
1267           },
1268           ::py::return_value_policy::reference_internal);
1269 }
1270 
1271 } // namespace python
1272 } // namespace dart
1273