Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Castable class #1634

Merged
merged 2 commits into from
Dec 23, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/PULL_REQUEST_TEMPLATE.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
57 changes: 11 additions & 46 deletions dart/collision/bullet/BulletCollisionDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -495,23 +495,17 @@ BulletCollisionDetector::createBulletCollisionShape(
using dynamics::SoftMeshShape;
using dynamics::SphereShape;

if (shape->is<SphereShape>())
if (const auto sphere = shape->as<SphereShape>())
{
assert(dynamic_cast<const SphereShape*>(shape.get()));

const auto sphere = static_cast<const SphereShape*>(shape.get());
const auto radius = sphere->getRadius();

auto bulletCollisionShape = std::make_unique<btSphereShape>(radius);

return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<BoxShape>())
else if (const auto box = shape->as<BoxShape>())
{
assert(dynamic_cast<const BoxShape*>(shape.get()));

const auto box = static_cast<const BoxShape*>(shape.get());
const Eigen::Vector3d& size = box->getSize();

auto bulletCollisionShape
Expand All @@ -520,11 +514,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<EllipsoidShape>())
else if (const auto ellipsoid = shape->as<EllipsoidShape>())
{
assert(dynamic_cast<const EllipsoidShape*>(shape.get()));

const auto ellipsoid = static_cast<const EllipsoidShape*>(shape.get());
const Eigen::Vector3d& radii = ellipsoid->getRadii();

auto bulletCollisionShape = createBulletEllipsoidMesh(
Expand All @@ -533,11 +524,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<CylinderShape>())
else if (const auto cylinder = shape->as<CylinderShape>())
{
assert(dynamic_cast<const CylinderShape*>(shape.get()));

const auto cylinder = static_cast<const CylinderShape*>(shape.get());
const auto radius = cylinder->getRadius();
const auto height = cylinder->getHeight();
const auto size = btVector3(radius, radius, height * 0.5);
Expand All @@ -547,11 +535,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<CapsuleShape>())
else if (const auto capsule = shape->as<CapsuleShape>())
{
assert(dynamic_cast<const CapsuleShape*>(shape.get()));

const auto capsule = static_cast<const CapsuleShape*>(shape.get());
const auto radius = capsule->getRadius();
const auto height = capsule->getHeight();

Expand All @@ -561,11 +546,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<ConeShape>())
else if (const auto cone = shape->as<ConeShape>())
{
assert(dynamic_cast<const ConeShape*>(shape.get()));

const auto cone = static_cast<const ConeShape*>(shape.get());
const auto radius = cone->getRadius();
const auto height = cone->getHeight();

Expand All @@ -579,11 +561,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<PlaneShape>())
else if (const auto plane = shape->as<PlaneShape>())
{
assert(dynamic_cast<const PlaneShape*>(shape.get()));

const auto plane = static_cast<const PlaneShape*>(shape.get());
const Eigen::Vector3d normal = plane->getNormal();
const double offset = plane->getOffset();

Expand All @@ -593,12 +572,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<MultiSphereConvexHullShape>())
else if (const auto multiSphere = shape->as<MultiSphereConvexHullShape>())
{
assert(dynamic_cast<const MultiSphereConvexHullShape*>(shape.get()));

const auto multiSphere
= static_cast<const MultiSphereConvexHullShape*>(shape.get());
const auto numSpheres = multiSphere->getNumSpheres();
const auto& spheres = multiSphere->getSpheres();

Expand All @@ -617,11 +592,8 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<MeshShape>())
else if (const auto shapeMesh = shape->as<MeshShape>())
{
assert(dynamic_cast<const MeshShape*>(shape.get()));

const auto shapeMesh = static_cast<const MeshShape*>(shape.get());
const auto scale = shapeMesh->getScale();
const auto mesh = shapeMesh->getMesh();

Expand All @@ -631,24 +603,17 @@ BulletCollisionDetector::createBulletCollisionShape(
return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<SoftMeshShape>())
else if (const auto softMeshShape = shape->as<SoftMeshShape>())
{
assert(dynamic_cast<const SoftMeshShape*>(shape.get()));

const auto softMeshShape = static_cast<const SoftMeshShape*>(shape.get());
const auto mesh = softMeshShape->getAssimpMesh();

auto bulletCollisionShape = createBulletCollisionShapeFromAssimpMesh(mesh);

return std::make_unique<BulletCollisionShape>(
std::move(bulletCollisionShape));
}
else if (shape->is<HeightmapShapef>())
else if (const auto heightMap = shape->as<HeightmapShapef>())
{
assert(dynamic_cast<const HeightmapShapef*>(shape.get()));

const auto heightMap = static_cast<const HeightmapShapef*>(shape.get());

return createBulletCollisionShapeFromHeightmap(heightMap);
}
else if (shape->is<HeightmapShaped>())
Expand Down
24 changes: 8 additions & 16 deletions dart/collision/ode/OdeCollisionObject.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,60 +185,52 @@ detail::OdeGeom* createOdeGeom(
detail::OdeGeom* geom = nullptr;
const auto shape = shapeFrame->getShape().get();

if (shape->is<SphereShape>())
if (const auto sphere = shape->as<SphereShape>())
{
const auto sphere = static_cast<const SphereShape*>(shape);
const auto radius = sphere->getRadius();

geom = new detail::OdeSphere(collObj, radius);
}
else if (shape->is<BoxShape>())
else if (const auto box = shape->as<BoxShape>())
{
const auto box = static_cast<const BoxShape*>(shape);
const Eigen::Vector3d& size = box->getSize();

geom = new detail::OdeBox(collObj, size);
}
else if (shape->is<CapsuleShape>())
else if (const auto capsule = shape->as<CapsuleShape>())
{
const auto capsule = static_cast<const CapsuleShape*>(shape);
const auto radius = capsule->getRadius();
const auto height = capsule->getHeight();

geom = new detail::OdeCapsule(collObj, radius, height);
}
else if (shape->is<CylinderShape>())
else if (const auto cylinder = shape->as<CylinderShape>())
{
const auto cylinder = static_cast<const CylinderShape*>(shape);
const auto radius = cylinder->getRadius();
const auto height = cylinder->getHeight();

geom = new detail::OdeCylinder(collObj, radius, height);
}
else if (shape->is<PlaneShape>())
else if (const auto plane = shape->as<PlaneShape>())
{
const auto plane = static_cast<const PlaneShape*>(shape);
const Eigen::Vector3d normal = plane->getNormal();
const double offset = plane->getOffset();

geom = new detail::OdePlane(collObj, normal, offset);
}
else if (shape->is<MeshShape>())
else if (const auto shapeMesh = shape->as<MeshShape>())
{
auto shapeMesh = static_cast<const MeshShape*>(shape);
const Eigen::Vector3d& scale = shapeMesh->getScale();
auto aiScene = shapeMesh->getMesh();

geom = new detail::OdeMesh(collObj, aiScene, scale);
}
else if (shape->is<HeightmapShapef>())
else if (const auto heightMap = shape->as<HeightmapShapef>())
{
auto heightMap = static_cast<const HeightmapShapef*>(shape);
geom = new detail::OdeHeightmapf(collObj, heightMap);
}
else if (shape->is<HeightmapShaped>())
else if (const auto heightMap = shape->as<HeightmapShaped>())
{
auto heightMap = static_cast<const HeightmapShaped*>(shape);
geom = new detail::OdeHeightmapd(collObj, heightMap);
}
else
Expand Down
62 changes: 49 additions & 13 deletions dart/dynamics/detail/Shape.hpp → dart/common/Castable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename ShapeT>
bool Shape::is() const
/// A CRTP base class that provides an interface for easily casting to the
/// derived types.
template <typename Base>
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<Sphere>())
/// std::cout << "The shape type is sphere!\n";
/// \endcode
template <typename Derived>
[[nodiscard]] bool is() const;

/// Casts to pointer of Derived if Base is its base class. Returns nullptr
/// otherwise.
template <typename Derived>
[[nodiscard]] const Derived* as() const;

/// Casts to pointer of Derived if Base is its base class. Returns nullptr
/// otherwise.
template <typename Derived>
[[nodiscard]] Derived* as();

/// Casts to reference of Derived if Base is its base class. UB otherwise.
template <typename Derived>
[[nodiscard]] const Derived& as_ref() const;

/// Casts to reference of Derived if Base is its base class. UB otherwise.
template <typename Derived>
[[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_
68 changes: 68 additions & 0 deletions dart/common/Metaprogramming.hpp
Original file line number Diff line number Diff line change
@@ -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 <typename T, typename = std::true_type> \
struct Alias_##member; \
\
template <typename T> \
struct Alias_##member< \
T, \
::std::integral_constant< \
bool, \
::dart::common::detail::got_type<decltype(&T::member)>::value>> \
{ \
static const decltype(&T::member) value; \
}; \
\
struct AmbiguitySeed_##member \
{ \
char member; \
}; \
\
template <typename T> \
struct has_member_##member \
{ \
static const bool value = ::dart::common::detail::has_member< \
Alias_##member< \
::dart::common::detail::ambiguate<T, AmbiguitySeed_##member>>, \
Alias_##member<AmbiguitySeed_##member>>::value; \
}

#include "dart/common/detail/Metaprogramming-impl.hpp"

#endif // DART_COMMON_METAPROGRAMMING_HPP_
Loading