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 Shape::getType() and deprecate Shape::getShapeType() #725

Merged
merged 6 commits into from
May 14, 2016
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
20 changes: 16 additions & 4 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,17 @@
## DART 6

### DART 6.1.0 (2016-XX-XX)

* Misc improvements and bug fixes

* Added `virtual Shape::getType()` and deprecated `ShapeType Shpae::getShapeType()`: [#724](https://github.com/dartsim/dart/pull/724)

### DART 6.0.1 (2016-XX-XX)

* Collision detection

* Added warnings for unsupported shape pairs of DARTCollisionDetector: [#722](https://github.com/dartsim/dart/pull/722)

### DART 6.0.0 (2016-05-10)

* Common data structures
Expand All @@ -9,7 +21,7 @@
* Added `ShapeFrame` and `ShapeNode`: [#608](https://github.com/dartsim/dart/pull/608)
* Added `BoundingBox`: [#547](https://github.com/dartsim/dart/pull/547), [#546](https://github.com/dartsim/dart/issues/546)

* Kinematics features:
* Kinematics

* Added convenient functions for setting joint limits: [#703](https://github.com/dartsim/dart/pull/703)
* Added more description on `InverseKinematics::solve()`: [#624](https://github.com/dartsim/dart/pull/624)
Expand All @@ -24,7 +36,7 @@
* Fixed `InverseKinematics` when it's used with `FreeJoint` and `BallJoint`: [#683](https://github.com/dartsim/dart/pull/683)
* Fixed ambiguous overload on `MetaSkeleton::getLinearJacobianDeriv`: [#628](https://github.com/dartsim/dart/pull/628), [#626](https://github.com/dartsim/dart/issues/626)

* Dynamics features:
* Dynamics

* Added `get/setLCPSolver` functions to `ConstraintSolver`: [#633](https://github.com/dartsim/dart/pull/633)
* Added `ServoMotorConstraint` as a preliminary implementation for `SERVO` actuator type: [#566](https://github.com/dartsim/dart/pull/566)
Expand All @@ -34,7 +46,7 @@
* Fixed incorrect applying of joint constraint impulses: [#317](https://github.com/dartsim/dart/issues/317)
* Deprecated `draw()` functions of dynamics classes: [#654](https://github.com/dartsim/dart/pull/654)

* Collision detection features
* Collision detection

* Added `CollisionGroup` and refactored `CollisionDetector` to be more versatile: [#711](https://github.com/dartsim/dart/pull/711), [#704](https://github.com/dartsim/dart/pull/704), [#689](https://github.com/dartsim/dart/pull/689), [#631](https://github.com/dartsim/dart/pull/631), [#642](https://github.com/dartsim/dart/issues/642), [#20](https://github.com/dartsim/dart/issues/20)
* Improved API for self collision checking options: [#718](https://github.com/dartsim/dart/pull/718), [#702](https://github.com/dartsim/dart/issues/702)
Expand All @@ -51,7 +63,7 @@
* Moved `osgDart` under `dart::gui` namespace as `dart::gui::osg`: [#651](https://github.com/dartsim/dart/pull/651)
* Fixed GlutWindow::screenshot(): [#623](https://github.com/dartsim/dart/pull/623), [#395](https://github.com/dartsim/dart/issues/395)

* Simulation features
* Simulation

* Fixed `World::clone()` didn't clone the collision detector: [#658](https://github.com/dartsim/dart/pull/658)
* Fixed bug of `World` concurrency: [#577](https://github.com/dartsim/dart/pull/577), [#576](https://github.com/dartsim/dart/issues/576)
Expand Down
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ endif()
project(dart)

set(DART_MAJOR_VERSION "6")
set(DART_MINOR_VERSION "0")
set(DART_MINOR_VERSION "1")
set(DART_PATCH_VERSION "0")
set(DART_VERSION "${DART_MAJOR_VERSION}.${DART_MINOR_VERSION}.${DART_PATCH_VERSION}")
set(DART_PKG_DESC "Dynamic Animation and Robotics Toolkit.")
Expand Down
135 changes: 60 additions & 75 deletions dart/collision/bullet/BulletCollisionDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -403,100 +403,85 @@ btCollisionShape* BulletCollisionDetector::createBulletCollisionShape(
using dynamics::MeshShape;
using dynamics::SoftMeshShape;

const auto& shapeType = shape->getType();
btCollisionShape* bulletCollisionShape = nullptr;

switch (shape->getShapeType())
if (BoxShape::getStaticType() == shapeType)
{
case Shape::BOX:
{
assert(dynamic_cast<const BoxShape*>(shape.get()));

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

bulletCollisionShape = new btBoxShape(convertVector3(size*0.5));
assert(dynamic_cast<const BoxShape*>(shape.get()));

break;
}
case Shape::ELLIPSOID:
{
assert(dynamic_cast<const EllipsoidShape*>(shape.get()));
const auto box = static_cast<const BoxShape*>(shape.get());
const Eigen::Vector3d& size = box->getSize();

const auto ellipsoid = static_cast<const EllipsoidShape*>(shape.get());
const Eigen::Vector3d& size = ellipsoid->getSize();
bulletCollisionShape = new btBoxShape(convertVector3(size*0.5));
}
else if (EllipsoidShape::getStaticType() == shapeType)
{
assert(dynamic_cast<const EllipsoidShape*>(shape.get()));

if (ellipsoid->isSphere())
{
bulletCollisionShape = new btSphereShape(size[0] * 0.5);
}
else
{
bulletCollisionShape = createBulletEllipsoidMesh(
size[0], size[1], size[2]);
}
const auto ellipsoid = static_cast<const EllipsoidShape*>(shape.get());
const Eigen::Vector3d& size = ellipsoid->getSize();

break;
}
case Shape::CYLINDER:
if (ellipsoid->isSphere())
{
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);

bulletCollisionShape = new btCylinderShapeZ(size);

break;
bulletCollisionShape = new btSphereShape(size[0] * 0.5);
}
case Shape::PLANE:
else
{
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();

bulletCollisionShape = new btStaticPlaneShape(
convertVector3(normal), offset);

break;
bulletCollisionShape = createBulletEllipsoidMesh(
size[0], size[1], size[2]);
}
case Shape::MESH:
{
assert(dynamic_cast<const MeshShape*>(shape.get()));
}
else if (CylinderShape::getStaticType() == shapeType)
{
assert(dynamic_cast<const CylinderShape*>(shape.get()));

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

bulletCollisionShape = createBulletCollisionShapeFromAssimpScene(
scale, mesh);
bulletCollisionShape = new btCylinderShapeZ(size);
}
else if (PlaneShape::getStaticType() == shapeType)
{
assert(dynamic_cast<const PlaneShape*>(shape.get()));

break;
}
case Shape::SOFT_MESH:
{
assert(dynamic_cast<const SoftMeshShape*>(shape.get()));
const auto plane = static_cast<const PlaneShape*>(shape.get());
const Eigen::Vector3d normal = plane->getNormal();
const double offset = plane->getOffset();

bulletCollisionShape = new btStaticPlaneShape(
convertVector3(normal), offset);
}
else if (MeshShape::getStaticType() == shapeType)
{
assert(dynamic_cast<const MeshShape*>(shape.get()));

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

bulletCollisionShape = createBulletCollisionShapeFromAssimpMesh(mesh);
bulletCollisionShape = createBulletCollisionShapeFromAssimpScene(
scale, mesh);
}
else if (SoftMeshShape::getStaticType() == shapeType)
{
assert(dynamic_cast<const SoftMeshShape*>(shape.get()));

break;
}
default:
{
dterr << "[BulletCollisionObjectData::init] "
<< "Attempting to create unsupported shape type '"
<< shape->getShapeType() << "'.\n";
const auto softMeshShape = static_cast<const SoftMeshShape*>(shape.get());
const auto mesh = softMeshShape->getAssimpMesh();

bulletCollisionShape = new btSphereShape(0.1);
bulletCollisionShape = createBulletCollisionShapeFromAssimpMesh(mesh);
}
else
{
dterr << "[BulletCollisionDetector::createBulletCollisionShape] "
<< "Attempting to create an unsupported shape type ["
<< shapeType << "] Creating a sphere with 0.1 radius "
<< "instead.\n";

break;
}
bulletCollisionShape = new btSphereShape(0.1);
}

return bulletCollisionShape;
Expand Down
116 changes: 52 additions & 64 deletions dart/collision/dart/DARTCollide.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,11 @@

#include <memory>

#include "dart/math/Helpers.hpp"
#include "dart/dynamics/BoxShape.hpp"
#include "dart/dynamics/EllipsoidShape.hpp"
#include "dart/dynamics/CylinderShape.hpp"
#include "dart/dynamics/BodyNode.hpp"
#include "dart/math/Helpers.hpp"

namespace dart {
namespace collision {
Expand Down Expand Up @@ -1258,83 +1258,71 @@ int collide(CollisionObject* o1, CollisionObject* o2, CollisionResult& result)
// TODO(JS): We could make the contact point computation as optional for
// the case that we want only binary check.

const dynamics::ConstShapePtr& shape0 = o1->getShape();
const dynamics::ConstShapePtr& shape1 = o2->getShape();
const Eigen::Isometry3d& T0 = o1->getTransform();
const Eigen::Isometry3d& T1 = o2->getTransform();
const auto& shape1 = o1->getShape();
const auto& shape2 = o2->getShape();

dynamics::Shape::ShapeType LeftType = shape0->getShapeType();
dynamics::Shape::ShapeType RightType = shape1->getShapeType();
const auto& shapeType1 = shape1->getType();
const auto& shapeType2 = shape2->getType();

switch(LeftType)
{
case dynamics::Shape::BOX:
{
const dynamics::BoxShape* box0 = static_cast<const dynamics::BoxShape*>(shape0.get());
const Eigen::Isometry3d& T1 = o1->getTransform();
const Eigen::Isometry3d& T2 = o2->getTransform();

switch(RightType)
{
case dynamics::Shape::BOX:
{
const dynamics::BoxShape* box1 = static_cast<const dynamics::BoxShape*>(shape1.get());
return collideBoxBox(o1, o2,
box0->getSize(), T0,
box1->getSize(), T1, result);
}
case dynamics::Shape::ELLIPSOID:
{
const dynamics::EllipsoidShape* ellipsoid1 = static_cast<const dynamics::EllipsoidShape*>(shape1.get());
return collideBoxSphere(o1, o2,
box0->getSize(), T0,
ellipsoid1->getSize()[0] * 0.5, T1,
result);
}
default:
{
return false;
if (dynamics::BoxShape::getStaticType() == shapeType1)
{
const auto* box0 = static_cast<const dynamics::BoxShape*>(shape1.get());

break;
}
}
if (dynamics::BoxShape::getStaticType() == shapeType2)
{
const auto* box1
= static_cast<const dynamics::BoxShape*>(shape2.get());

break;
return collideBoxBox(o1, o2,
box0->getSize(), T1,
box1->getSize(), T2,
result);
}
case dynamics::Shape::ELLIPSOID:
else if (dynamics::EllipsoidShape::getStaticType() == shapeType2)
{
const dynamics::EllipsoidShape* ellipsoid0 = static_cast<const dynamics::EllipsoidShape*>(shape0.get());
const auto* ellipsoid1
= static_cast<const dynamics::EllipsoidShape*>(shape2.get());

switch(RightType)
{
case dynamics::Shape::BOX:
{
const dynamics::BoxShape* box1 = static_cast<const dynamics::BoxShape*>(shape1.get());
return collideSphereBox(o1, o2,
ellipsoid0->getSize()[0] * 0.5, T0,
box1->getSize(), T1,
result);
}
case dynamics::Shape::ELLIPSOID:
{
const dynamics::EllipsoidShape* ellipsoid1 = static_cast<const dynamics::EllipsoidShape*>(shape1.get());
return collideSphereSphere(o1, o2,
ellipsoid0->getSize()[0] * 0.5, T0,
ellipsoid1->getSize()[0] * 0.5, T1,
result);
}
default:
return false;
return collideBoxSphere(o1, o2,
box0->getSize(), T1,
ellipsoid1->getSize()[0] * 0.5, T2,
result);
}
}
else if (dynamics::EllipsoidShape::getStaticType() == shapeType1)
{
const auto* ellipsoid0
= static_cast<const dynamics::EllipsoidShape*>(shape1.get());

break;
}
if (dynamics::BoxShape::getStaticType() == shapeType2)
{
const auto* box1
= static_cast<const dynamics::BoxShape*>(shape2.get());

break;
return collideSphereBox(o1, o2,
ellipsoid0->getSize()[0] * 0.5, T1,
box1->getSize(), T2,
result);
}
default:
return false;
else if (dynamics::EllipsoidShape::getStaticType() == shapeType2)
{
const auto* ellipsoid1
= static_cast<const dynamics::EllipsoidShape*>(shape2.get());

break;
return collideSphereSphere(o1, o2,
ellipsoid0->getSize()[0] * 0.5, T1,
ellipsoid1->getSize()[0] * 0.5, T2,
result);
}
}

dterr << "[DARTCollisionDetector] Attempting to check for an "
<< "unsupported shape pair: [" << shape1->getType()
<< "] - [" << shape2->getType() << "]. Returning false.\n";

return false;
}

Expand Down
9 changes: 0 additions & 9 deletions dart/collision/dart/DARTCollide.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,17 +38,8 @@
#define DART_COLLISION_DART_DARTCOLLIDE_HPP_

#include <vector>

#include <Eigen/Dense>

#include "dart/collision/CollisionDetector.hpp"
#include "dart/dynamics/Shape.hpp"

namespace dart {
namespace dynamics {
class Shape;
} // namespace dynamics
} // namespace dart

namespace dart {
namespace collision {
Expand Down
Loading