diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index 7f6de5bf6ee4a..fd8c6d4c762a9 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -6,7 +6,7 @@ - [ ] Document new methods and classes - [ ] Format new code files using ClangFormat by running `make format` -- [ ] Build with `-DDART_TREAT_WARNINGS_AS_ERRORS=ON` and resolve build warnings +- [ ] Build with `-DDART_TREAT_WARNINGS_AS_ERRORS=ON` and resolve all the compile warnings #### Before merging a pull request diff --git a/CHANGELOG.md b/CHANGELOG.md index 4752456ee73d3..a10b835d45e69 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,10 @@ ### [DART 6.13.0 (TBD)](https://github.com/dartsim/dart/milestone/69?closed=1) +* Common + + * Added Castable class: [#1634](https://github.com/dartsim/dart/pull/1634) + * Dynamics * Added deep copy for shapes: [#1612](https://github.com/dartsim/dart/pull/1612) diff --git a/dart/collision/bullet/BulletCollisionDetector.cpp b/dart/collision/bullet/BulletCollisionDetector.cpp index 5e5574bbe639f..e7ccf1f49432b 100644 --- a/dart/collision/bullet/BulletCollisionDetector.cpp +++ b/dart/collision/bullet/BulletCollisionDetector.cpp @@ -495,11 +495,8 @@ BulletCollisionDetector::createBulletCollisionShape( using dynamics::SoftMeshShape; using dynamics::SphereShape; - if (shape->is()) + if (const auto sphere = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto sphere = static_cast(shape.get()); const auto radius = sphere->getRadius(); auto bulletCollisionShape = std::make_unique(radius); @@ -507,11 +504,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto box = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto box = static_cast(shape.get()); const Eigen::Vector3d& size = box->getSize(); auto bulletCollisionShape @@ -520,11 +514,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto ellipsoid = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto ellipsoid = static_cast(shape.get()); const Eigen::Vector3d& radii = ellipsoid->getRadii(); auto bulletCollisionShape = createBulletEllipsoidMesh( @@ -533,11 +524,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto cylinder = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto cylinder = static_cast(shape.get()); const auto radius = cylinder->getRadius(); const auto height = cylinder->getHeight(); const auto size = btVector3(radius, radius, height * 0.5); @@ -547,11 +535,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto capsule = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto capsule = static_cast(shape.get()); const auto radius = capsule->getRadius(); const auto height = capsule->getHeight(); @@ -561,11 +546,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto cone = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto cone = static_cast(shape.get()); const auto radius = cone->getRadius(); const auto height = cone->getHeight(); @@ -579,11 +561,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto plane = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto plane = static_cast(shape.get()); const Eigen::Vector3d normal = plane->getNormal(); const double offset = plane->getOffset(); @@ -593,12 +572,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto multiSphere = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto multiSphere - = static_cast(shape.get()); const auto numSpheres = multiSphere->getNumSpheres(); const auto& spheres = multiSphere->getSpheres(); @@ -617,11 +592,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto shapeMesh = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto shapeMesh = static_cast(shape.get()); const auto scale = shapeMesh->getScale(); const auto mesh = shapeMesh->getMesh(); @@ -631,11 +603,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto softMeshShape = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto softMeshShape = static_cast(shape.get()); const auto mesh = softMeshShape->getAssimpMesh(); auto bulletCollisionShape = createBulletCollisionShapeFromAssimpMesh(mesh); @@ -643,12 +612,8 @@ BulletCollisionDetector::createBulletCollisionShape( return std::make_unique( std::move(bulletCollisionShape)); } - else if (shape->is()) + else if (const auto heightMap = shape->as()) { - assert(dynamic_cast(shape.get())); - - const auto heightMap = static_cast(shape.get()); - return createBulletCollisionShapeFromHeightmap(heightMap); } else if (shape->is()) diff --git a/dart/collision/ode/OdeCollisionObject.cpp b/dart/collision/ode/OdeCollisionObject.cpp index 3a6a1f05e758d..ddd0ac736e32d 100644 --- a/dart/collision/ode/OdeCollisionObject.cpp +++ b/dart/collision/ode/OdeCollisionObject.cpp @@ -185,60 +185,52 @@ detail::OdeGeom* createOdeGeom( detail::OdeGeom* geom = nullptr; const auto shape = shapeFrame->getShape().get(); - if (shape->is()) + if (const auto sphere = shape->as()) { - const auto sphere = static_cast(shape); const auto radius = sphere->getRadius(); geom = new detail::OdeSphere(collObj, radius); } - else if (shape->is()) + else if (const auto box = shape->as()) { - const auto box = static_cast(shape); const Eigen::Vector3d& size = box->getSize(); geom = new detail::OdeBox(collObj, size); } - else if (shape->is()) + else if (const auto capsule = shape->as()) { - const auto capsule = static_cast(shape); const auto radius = capsule->getRadius(); const auto height = capsule->getHeight(); geom = new detail::OdeCapsule(collObj, radius, height); } - else if (shape->is()) + else if (const auto cylinder = shape->as()) { - const auto cylinder = static_cast(shape); const auto radius = cylinder->getRadius(); const auto height = cylinder->getHeight(); geom = new detail::OdeCylinder(collObj, radius, height); } - else if (shape->is()) + else if (const auto plane = shape->as()) { - const auto plane = static_cast(shape); const Eigen::Vector3d normal = plane->getNormal(); const double offset = plane->getOffset(); geom = new detail::OdePlane(collObj, normal, offset); } - else if (shape->is()) + else if (const auto shapeMesh = shape->as()) { - auto shapeMesh = static_cast(shape); const Eigen::Vector3d& scale = shapeMesh->getScale(); auto aiScene = shapeMesh->getMesh(); geom = new detail::OdeMesh(collObj, aiScene, scale); } - else if (shape->is()) + else if (const auto heightMap = shape->as()) { - auto heightMap = static_cast(shape); geom = new detail::OdeHeightmapf(collObj, heightMap); } - else if (shape->is()) + else if (const auto heightMap = shape->as()) { - auto heightMap = static_cast(shape); geom = new detail::OdeHeightmapd(collObj, heightMap); } else diff --git a/dart/dynamics/detail/Shape.hpp b/dart/common/Castable.hpp similarity index 51% rename from dart/dynamics/detail/Shape.hpp rename to dart/common/Castable.hpp index a2ee41747c679..3b3d590305477 100644 --- a/dart/dynamics/detail/Shape.hpp +++ b/dart/common/Castable.hpp @@ -30,21 +30,57 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef DART_DYNAMICS_DETAIL_SHAPE_HPP_ -#define DART_DYNAMICS_DETAIL_SHAPE_HPP_ +#ifndef DART_COMMON_CASTABLE_HPP_ +#define DART_COMMON_CASTABLE_HPP_ -#include "dart/dynamics/Shape.hpp" +namespace dart::common { -namespace dart { -namespace dynamics { - -template -bool Shape::is() const +/// A CRTP base class that provides an interface for easily casting to the +/// derived types. +template +class Castable { - return getType() == ShapeT::getStaticType(); -} +public: + /// Returns true if the types of this \c Base and the template parameter (a + /// base class) are identical. This function is a syntactic sugar, which + /// is identical to: (getType() == ShapeType::getStaticType()). + /// + /// Example code: + /// \code + /// if (shape->is()) + /// std::cout << "The shape type is sphere!\n"; + /// \endcode + template + [[nodiscard]] bool is() const; + + /// Casts to pointer of Derived if Base is its base class. Returns nullptr + /// otherwise. + template + [[nodiscard]] const Derived* as() const; + + /// Casts to pointer of Derived if Base is its base class. Returns nullptr + /// otherwise. + template + [[nodiscard]] Derived* as(); + + /// Casts to reference of Derived if Base is its base class. UB otherwise. + template + [[nodiscard]] const Derived& as_ref() const; + + /// Casts to reference of Derived if Base is its base class. UB otherwise. + template + [[nodiscard]] Derived& as_ref(); + +private: + /// Casts to Base const-reference + [[nodiscard]] const Base& base() const; + + /// Casts to Base reference + [[nodiscard]] Base& base(); +}; + +} // namespace dart::common -} // namespace dynamics -} // namespace dart +#include "dart/common/detail/Castable-impl.hpp" -#endif // DART_DYNAMICS_DETAIL_SHAPE_HPP_ +#endif // DART_COMMON_CASTABLE_HPP_ diff --git a/dart/common/Metaprogramming.hpp b/dart/common/Metaprogramming.hpp new file mode 100644 index 0000000000000..24fae243c5e5a --- /dev/null +++ b/dart/common/Metaprogramming.hpp @@ -0,0 +1,68 @@ +/* + * Copyright (c) 2011-2021, The DART development contributors + * All rights reserved. + * + * The list of contributors can be found at: + * https://github.com/dartsim/dart/blob/master/LICENSE + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DART_COMMON_METAPROGRAMMING_HPP_ +#define DART_COMMON_METAPROGRAMMING_HPP_ + +// Check for any member with given name, whether var, func, class, union, enum. +#define DART_CREATE_MEMBER_CHECK(member) \ + \ + template \ + struct Alias_##member; \ + \ + template \ + struct Alias_##member< \ + T, \ + ::std::integral_constant< \ + bool, \ + ::dart::common::detail::got_type::value>> \ + { \ + static const decltype(&T::member) value; \ + }; \ + \ + struct AmbiguitySeed_##member \ + { \ + char member; \ + }; \ + \ + template \ + struct has_member_##member \ + { \ + static const bool value = ::dart::common::detail::has_member< \ + Alias_##member< \ + ::dart::common::detail::ambiguate>, \ + Alias_##member>::value; \ + } + +#include "dart/common/detail/Metaprogramming-impl.hpp" + +#endif // DART_COMMON_METAPROGRAMMING_HPP_ diff --git a/dart/common/detail/Castable-impl.hpp b/dart/common/detail/Castable-impl.hpp new file mode 100644 index 0000000000000..da0e69b2a32f5 --- /dev/null +++ b/dart/common/detail/Castable-impl.hpp @@ -0,0 +1,112 @@ +/* + * Copyright (c) 2011-2021, The DART development contributors + * All rights reserved. + * + * The list of contributors can be found at: + * https://github.com/dartsim/dart/blob/master/LICENSE + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DART_COMMON_DETAIL_CASTABLE_HPP_ +#define DART_COMMON_DETAIL_CASTABLE_HPP_ + +#include "dart/common/Castable.hpp" +#include "dart/common/Metaprogramming.hpp" + +namespace dart::common { + +//============================================================================== +DART_CREATE_MEMBER_CHECK(getType); +DART_CREATE_MEMBER_CHECK(getStaticType); + +//============================================================================== +template +template +bool Castable::is() const +{ + if constexpr ( + has_member_getType::value + && has_member_getStaticType::value) + { + return (base().getType() == Derived::getStaticType()); + } + else + { + return (dynamic_cast(&base()) != nullptr); + } +} + +//============================================================================== +template +template +const Derived* Castable::as() const +{ + return is() ? static_cast(&base()) : nullptr; +} + +//============================================================================== +template +template +Derived* Castable::as() +{ + return is() ? static_cast(&base()) : nullptr; +} + +//============================================================================== +template +template +const Derived& Castable::as_ref() const +{ + assert(is()); + return *as(); +} + +//============================================================================== +template +template +Derived& Castable::as_ref() +{ + assert(is()); + return *as(); +} + +//============================================================================== +template +const Base& Castable::base() const +{ + return *static_cast(this); +} + +//============================================================================== +template +Base& Castable::base() +{ + return *static_cast(this); +} + +} // namespace dart::common + +#endif // DART_COMMON_DETAIL_CASTABLE_HPP_ diff --git a/dart/constraint/detail/BoxedLcpSolver-impl.hpp b/dart/common/detail/Metaprogramming-impl.hpp similarity index 54% rename from dart/constraint/detail/BoxedLcpSolver-impl.hpp rename to dart/common/detail/Metaprogramming-impl.hpp index a7c1d772828c4..c14e951ddbfa5 100644 --- a/dart/constraint/detail/BoxedLcpSolver-impl.hpp +++ b/dart/common/detail/Metaprogramming-impl.hpp @@ -30,21 +30,60 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef DART_CONSTRAINT_DETAIL_BOXEDLCPSOLVER_IMPL_HPP_ -#define DART_CONSTRAINT_DETAIL_BOXEDLCPSOLVER_IMPL_HPP_ +#ifndef DART_COMMON_DETAIL_METAPROGRAMMING_HPP_ +#define DART_COMMON_DETAIL_METAPROGRAMMING_HPP_ -#include "dart/constraint/BoxedLcpSolver.hpp" +#include -namespace dart { -namespace constraint { +#include "dart/common/Metaprogramming.hpp" -template -bool BoxedLcpSolver::is() const +namespace dart::common::detail { + +// Inspired by https://stackoverflow.com/a/6324863/3122234 + +// Variadic to force ambiguity of class members. C++11 and up. +template +struct ambiguate : public Args... +{ +}; + +// Non-variadic version of the line above. +// template struct ambiguate : public A, public B {}; + +template +struct got_type : std::false_type +{ +}; + +template +struct got_type : std::true_type { - return getType() == BoxedLcpSolverT::getStaticType(); -} + using type = A; +}; + +template +struct sig_check : std::true_type +{ +}; + +template +struct has_member +{ + template + static char (&f(decltype(&C::value)))[1]; + + template + static char (&f(...))[2]; + + // Make sure the member name is consistently spelled the same. + static_assert( + (sizeof(f(0)) == 1), + "Member name specified in AmbiguitySeed is different from member name " + "specified in Alias, or wrong Alias/AmbiguitySeed has been specified."); + + static bool const value = sizeof(f(0)) == 2; +}; -} // namespace constraint -} // namespace dart +} // namespace dart::common::detail -#endif // DART_CONSTRAINT_DETAIL_BOXEDLCPSOLVER_IMPL_HPP_ +#endif // DART_COMMON_DETAIL_METAPROGRAMMING_HPP_ diff --git a/dart/constraint/BoxedLcpSolver.hpp b/dart/constraint/BoxedLcpSolver.hpp index 9ef1f28dab02f..49eef9dfca7ef 100644 --- a/dart/constraint/BoxedLcpSolver.hpp +++ b/dart/constraint/BoxedLcpSolver.hpp @@ -37,10 +37,12 @@ #include +#include "dart/common/Castable.hpp" + namespace dart { namespace constraint { -class BoxedLcpSolver +class BoxedLcpSolver : public common::Castable { public: /// Destructor @@ -49,22 +51,6 @@ class BoxedLcpSolver /// Returns the type virtual const std::string& getType() const = 0; - /// Returns true if this solver and the template parameter (a solver class) - /// are the same type. This function is a syntactic sugar, which is identical - /// to: - /// \code getType() == BoxedLcpSolver::getStaticType() \endcode. - /// - /// Example code: - /// \code - /// auto lcpSolver = constraintSolver->getBoxedLcpSolver(); - /// if (shape->is()) - /// std::cout << "The LCP solver type is Dantzig!\n"; - /// \endcode - /// - /// \sa getType() - template - bool is() const; - /// Solves constriant impulses for a constrained group. The LCP formulation /// setting that this function solve is A*x = b + w where each x[i], w[i] /// satisfies one of @@ -110,6 +96,4 @@ class BoxedLcpSolver } // namespace constraint } // namespace dart -#include "dart/constraint/detail/BoxedLcpSolver-impl.hpp" - #endif // DART_CONSTRAINT_BOXEDLCPSOLVER_HPP_ diff --git a/dart/dynamics/Shape.hpp b/dart/dynamics/Shape.hpp index 49d72118be41f..198226a2746a3 100644 --- a/dart/dynamics/Shape.hpp +++ b/dart/dynamics/Shape.hpp @@ -37,6 +37,7 @@ #include +#include "dart/common/Castable.hpp" #include "dart/common/ClassWithVirtualBase.hpp" #include "dart/common/Deprecated.hpp" #include "dart/common/Signal.hpp" @@ -50,7 +51,8 @@ namespace dynamics { DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN class Shape : public virtual common::Subject, - public virtual common::VersionCounter + public virtual common::VersionCounter, + public common::Castable { public: using VersionChangedSignal @@ -112,21 +114,6 @@ class Shape : public virtual common::Subject, /// \sa is() virtual const std::string& getType() const = 0; - /// Get true if the types of this Shape and the template parameter (a shape - /// class) are identical. This function is a syntactic sugar, which is - /// identical to: (getType() == ShapeType::getStaticType()). - /// - /// Example code: - /// \code - /// auto shape = bodyNode->getShapeNode(0)->getShape(); - /// if (shape->is()) - /// std::cout << "The shape type is box!\n"; - /// \endcode - /// - /// \sa getType() - template - bool is() const; - /// \brief Get the bounding box of the shape in its local coordinate frame. /// The dimension will be automatically determined by the sub-classes /// such as BoxShape, EllipsoidShape, CylinderShape, and MeshShape. @@ -239,6 +226,4 @@ DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_END } // namespace dynamics } // namespace dart -#include "dart/dynamics/detail/Shape.hpp" - #endif // DART_DYNAMICS_SHAPE_HPP_ diff --git a/dart/gui/glut/SimWindow.cpp b/dart/gui/glut/SimWindow.cpp index 6a7610bae80fe..ce723ef0a90fb 100644 --- a/dart/gui/glut/SimWindow.cpp +++ b/dart/gui/glut/SimWindow.cpp @@ -444,52 +444,41 @@ void SimWindow::drawShape( using dynamics::SoftMeshShape; using dynamics::SphereShape; - if (shape->is()) + if (const auto* sphere = shape->as()) { - const auto* sphere = static_cast(shape); mRI->drawSphere(sphere->getRadius()); } - else if (shape->is()) + else if (const auto* box = shape->as()) { - const auto* box = static_cast(shape); mRI->drawCube(box->getSize()); } - else if (shape->is()) + else if (const auto* ellipsoid = shape->as()) { - const auto* ellipsoid = static_cast(shape); mRI->drawEllipsoid(ellipsoid->getDiameters()); } - else if (shape->is()) + else if (const auto* cylinder = shape->as()) { - const auto* cylinder = static_cast(shape); mRI->drawCylinder(cylinder->getRadius(), cylinder->getHeight()); } - else if (shape->is()) + else if (const auto* capsule = shape->as()) { - const auto* capsule = static_cast(shape); mRI->drawCapsule(capsule->getRadius(), capsule->getHeight()); } - else if (shape->is()) + else if (const auto* cone = shape->as()) { - const auto* cone = static_cast(shape); mRI->drawCone(cone->getRadius(), cone->getHeight()); } - else if (shape->is()) + else if (const auto* pyramid = shape->as()) { - const auto* pyramid = static_cast(shape); mRI->drawPyramid( pyramid->getBaseWidth(), pyramid->getBaseDepth(), pyramid->getHeight()); } - else if (shape->is()) + else if (const auto* multiSphere = shape->as()) { - const auto* multiSphere - = static_cast(shape); mRI->drawMultiSphereConvexHull(multiSphere->getSpheres(), 3u); } - else if (shape->is()) + else if (const auto* mesh = shape->as()) { - const auto& mesh = static_cast(shape); - glDisable(GL_COLOR_MATERIAL); // Use mesh colors to draw if (mesh->getDisplayList()) @@ -497,14 +486,12 @@ void SimWindow::drawShape( else mRI->drawMesh(mesh->getScale(), mesh->getMesh()); } - else if (shape->is()) + else if (const auto* softMesh = shape->as()) { - const auto& softMesh = static_cast(shape); mRI->drawSoftMesh(softMesh->getAssimpMesh()); } - else if (shape->is()) + else if (const auto* lineSegmentShape = shape->as()) { - const auto& lineSegmentShape = static_cast(shape); mRI->drawLineSegments( lineSegmentShape->getVertices(), lineSegmentShape->getConnections()); }