From fadf20c2062f61af0903fae8647b8acc64da5087 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 30 Mar 2016 16:09:46 -0400 Subject: [PATCH 1/3] Deprecate draw functions of classes in dynamics namespace --- apps/addDeleteSkels/MyWindow.cpp | 4 +- apps/addDeleteSkels/MyWindow.h | 2 +- apps/atlasSimbicon/MyWindow.cpp | 2 +- apps/bipedStand/MyWindow.cpp | 6 +- apps/bipedStand/MyWindow.h | 2 +- apps/hardcodedDesign/MyWindow.cpp | 2 +- apps/hardcodedDesign/MyWindow.h | 4 +- apps/hybridDynamics/MyWindow.cpp | 4 +- apps/hybridDynamics/MyWindow.h | 2 +- apps/jointConstraints/MyWindow.cpp | 2 +- apps/mixedChain/MyWindow.cpp | 4 +- apps/mixedChain/MyWindow.h | 2 +- apps/operationalSpaceControl/MyWindow.cpp | 6 +- apps/operationalSpaceControl/MyWindow.h | 2 +- apps/rigidCubes/MyWindow.cpp | 4 +- apps/rigidCubes/MyWindow.h | 2 +- apps/rigidShapes/MyWindow.cpp | 4 +- apps/rigidShapes/MyWindow.h | 2 +- apps/softBodies/MyWindow.cpp | 6 +- apps/softBodies/MyWindow.h | 2 +- apps/vehicle/MyWindow.cpp | 4 +- apps/vehicle/MyWindow.h | 2 +- dart/dynamics/BodyNode.cpp | 8 + dart/dynamics/BodyNode.h | 2 + dart/dynamics/BoxShape.h | 1 + dart/dynamics/CylinderShape.h | 1 + dart/dynamics/EllipsoidShape.h | 1 + dart/dynamics/Entity.h | 1 + dart/dynamics/Frame.cpp | 4 + dart/dynamics/Frame.h | 1 + dart/dynamics/LineSegmentShape.h | 1 + dart/dynamics/Marker.cpp | 6 + dart/dynamics/Marker.h | 4 + dart/dynamics/MeshShape.h | 1 + dart/dynamics/PlaneShape.h | 2 +- dart/dynamics/PointMass.cpp | 38 +-- dart/dynamics/PointMass.h | 5 +- dart/dynamics/Shape.h | 2 +- dart/dynamics/ShapeFrame.cpp | 4 + dart/dynamics/ShapeFrame.h | 1 + dart/dynamics/Skeleton.cpp | 8 + dart/dynamics/Skeleton.h | 4 + dart/dynamics/SoftBodyNode.cpp | 10 + dart/dynamics/SoftBodyNode.h | 4 + dart/dynamics/SoftMeshShape.h | 1 + dart/gui/SimWindow.cpp | 317 +++++++++++++++++++++- dart/gui/SimWindow.h | 49 +++- dart/renderer/OpenGLRenderInterface.cpp | 88 ++++-- dart/renderer/OpenGLRenderInterface.h | 18 +- dart/renderer/RenderInterface.cpp | 5 + dart/renderer/RenderInterface.h | 1 + tutorials/tutorialCollisions-Finished.cpp | 4 +- tutorials/tutorialCollisions.cpp | 4 +- 53 files changed, 565 insertions(+), 101 deletions(-) diff --git a/apps/addDeleteSkels/MyWindow.cpp b/apps/addDeleteSkels/MyWindow.cpp index dd36b1692ee37..245ff81737c71 100644 --- a/apps/addDeleteSkels/MyWindow.cpp +++ b/apps/addDeleteSkels/MyWindow.cpp @@ -45,11 +45,11 @@ MyWindow::~MyWindow() { } -void MyWindow::drawSkels() { +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void MyWindow::keyboard(unsigned char _key, int _x, int _y) { diff --git a/apps/addDeleteSkels/MyWindow.h b/apps/addDeleteSkels/MyWindow.h index 8cab84fa13180..9cf17e572ec65 100644 --- a/apps/addDeleteSkels/MyWindow.h +++ b/apps/addDeleteSkels/MyWindow.h @@ -50,7 +50,7 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); /// \brief - virtual void drawSkels(); + virtual void drawWorld() const; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/atlasSimbicon/MyWindow.cpp b/apps/atlasSimbicon/MyWindow.cpp index 08af0a909af31..6a08f7b4e44f7 100644 --- a/apps/atlasSimbicon/MyWindow.cpp +++ b/apps/atlasSimbicon/MyWindow.cpp @@ -81,7 +81,7 @@ void MyWindow::drawSkels() // glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); for (unsigned int i = 0; i < mWorld->getNumSkeletons(); i++) - mWorld->getSkeleton(i)->draw(mRI); + drawSkeleton(mWorld->getSkeleton(i).get()); // draw arrow if (mImpulseDuration > 0) diff --git a/apps/bipedStand/MyWindow.cpp b/apps/bipedStand/MyWindow.cpp index 0aa9d529d821b..b0bebba657b78 100644 --- a/apps/bipedStand/MyWindow.cpp +++ b/apps/bipedStand/MyWindow.cpp @@ -62,9 +62,9 @@ void MyWindow::timeStepping() { } } -void MyWindow::drawSkels() { - for (unsigned int i = 0; i < mWorld->getNumSkeletons(); i++) - mWorld->getSkeleton(i)->draw(mRI); +void MyWindow::drawWorld() { + + SimWindow::drawWorld(); // draw arrow if (mImpulseDuration > 0) { diff --git a/apps/bipedStand/MyWindow.h b/apps/bipedStand/MyWindow.h index 7ead529d3c2b8..284b3a1bb8e94 100644 --- a/apps/bipedStand/MyWindow.h +++ b/apps/bipedStand/MyWindow.h @@ -52,7 +52,7 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); virtual void timeStepping(); - virtual void drawSkels(); + virtual void drawWorld(); virtual void keyboard(unsigned char _key, int _x, int _y); void setController(Controller* _controller); diff --git a/apps/hardcodedDesign/MyWindow.cpp b/apps/hardcodedDesign/MyWindow.cpp index 89401489cfbc8..eddcad0766e88 100644 --- a/apps/hardcodedDesign/MyWindow.cpp +++ b/apps/hardcodedDesign/MyWindow.cpp @@ -47,7 +47,7 @@ void MyWindow::draw() { glDisable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - skel->draw(mRI); + drawSkeleton(skel.get()); } void MyWindow::keyboard(unsigned char _key, int _x, int _y) { diff --git a/apps/hardcodedDesign/MyWindow.h b/apps/hardcodedDesign/MyWindow.h index a9ebad25506b6..012fb4f5c34a0 100644 --- a/apps/hardcodedDesign/MyWindow.h +++ b/apps/hardcodedDesign/MyWindow.h @@ -49,10 +49,10 @@ #include "dart/dart.h" -class MyWindow : public dart::gui::Win3D { +class MyWindow : public dart::gui::SimWindow { public: /// \brief The constructor - set the position of the skeleton - explicit MyWindow(dart::dynamics::SkeletonPtr _skel): Win3D(), skel(_skel) { + explicit MyWindow(dart::dynamics::SkeletonPtr _skel): SimWindow(), skel(_skel) { mTrans[1] = 200.f; mZoom = 0.3; } diff --git a/apps/hybridDynamics/MyWindow.cpp b/apps/hybridDynamics/MyWindow.cpp index dd4ea5365d8c8..09dc06eb27040 100644 --- a/apps/hybridDynamics/MyWindow.cpp +++ b/apps/hybridDynamics/MyWindow.cpp @@ -73,12 +73,12 @@ void MyWindow::timeStepping() } //============================================================================== -void MyWindow::drawSkels() +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } //============================================================================== diff --git a/apps/hybridDynamics/MyWindow.h b/apps/hybridDynamics/MyWindow.h index 1876a2ff6e8f6..c065282cf9fa8 100644 --- a/apps/hybridDynamics/MyWindow.h +++ b/apps/hybridDynamics/MyWindow.h @@ -53,7 +53,7 @@ class MyWindow : public dart::gui::SimWindow virtual void timeStepping(); /// \brief - virtual void drawSkels(); + virtual void drawWorld() const; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/jointConstraints/MyWindow.cpp b/apps/jointConstraints/MyWindow.cpp index 6235bea1ba0e5..b1c1e6f81f71f 100644 --- a/apps/jointConstraints/MyWindow.cpp +++ b/apps/jointConstraints/MyWindow.cpp @@ -65,7 +65,7 @@ void MyWindow::timeStepping() void MyWindow::drawSkels() { for (unsigned int i = 0; i < mWorld->getNumSkeletons(); i++) - mWorld->getSkeleton(i)->draw(mRI); + drawSkeleton(mWorld->getSkeleton(i).get()); // draw arrow if (mImpulseDuration > 0) diff --git a/apps/mixedChain/MyWindow.cpp b/apps/mixedChain/MyWindow.cpp index a67bf4083d209..ec22361dfe141 100644 --- a/apps/mixedChain/MyWindow.cpp +++ b/apps/mixedChain/MyWindow.cpp @@ -77,7 +77,7 @@ void MyWindow::timeStepping() mForceOnVertex /= 2.0; } -void MyWindow::drawSkels() +void MyWindow::drawWorld() { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); @@ -99,7 +99,7 @@ void MyWindow::drawSkels() dart::gui::drawArrow3D(start, mForceOnRigidBody, len, 0.025, 0.05); } - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void MyWindow::keyboard(unsigned char key, int x, int y) diff --git a/apps/mixedChain/MyWindow.h b/apps/mixedChain/MyWindow.h index 4f678a568172f..6e731bfd17b02 100644 --- a/apps/mixedChain/MyWindow.h +++ b/apps/mixedChain/MyWindow.h @@ -62,7 +62,7 @@ class MyWindow : public dart::gui::SoftSimWindow virtual void keyboard(unsigned char key, int x, int y); /// \brief - virtual void drawSkels(); + virtual void drawWorld(); private: /// \brief diff --git a/apps/operationalSpaceControl/MyWindow.cpp b/apps/operationalSpaceControl/MyWindow.cpp index 8ba491e0460d0..50a368ead6338 100644 --- a/apps/operationalSpaceControl/MyWindow.cpp +++ b/apps/operationalSpaceControl/MyWindow.cpp @@ -81,7 +81,7 @@ void MyWindow::timeStepping() } //============================================================================== -void MyWindow::drawSkels() +void MyWindow::drawWorld() { // Draw the target position if (mRI) @@ -93,8 +93,8 @@ void MyWindow::drawSkels() mRI->popMatrix(); } - // Draw skeletons - SimWindow::drawSkels(); + // Draw world + SimWindow::drawWorld(); } //============================================================================== diff --git a/apps/operationalSpaceControl/MyWindow.h b/apps/operationalSpaceControl/MyWindow.h index 0b95668c44a6e..334a501ab66e0 100644 --- a/apps/operationalSpaceControl/MyWindow.h +++ b/apps/operationalSpaceControl/MyWindow.h @@ -55,7 +55,7 @@ class MyWindow : public dart::gui::SimWindow virtual void timeStepping(); // Documentation inherited - virtual void drawSkels(); + virtual void drawWorld(); // Documentation inherited virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/rigidCubes/MyWindow.cpp b/apps/rigidCubes/MyWindow.cpp index 5fc82c0e3119e..143f37ad2458d 100644 --- a/apps/rigidCubes/MyWindow.cpp +++ b/apps/rigidCubes/MyWindow.cpp @@ -51,11 +51,11 @@ void MyWindow::timeStepping() { mForce /= 2.0; } -void MyWindow::drawSkels() { +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void MyWindow::keyboard(unsigned char _key, int _x, int _y) { diff --git a/apps/rigidCubes/MyWindow.h b/apps/rigidCubes/MyWindow.h index dc09b2aebf788..140b4d6b5e672 100644 --- a/apps/rigidCubes/MyWindow.h +++ b/apps/rigidCubes/MyWindow.h @@ -53,7 +53,7 @@ class MyWindow : public dart::gui::SimWindow { virtual void timeStepping(); /// \brief - virtual void drawSkels(); + virtual void drawWorld() const; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/rigidShapes/MyWindow.cpp b/apps/rigidShapes/MyWindow.cpp index c552f1a0e9d85..9dc32730715f1 100644 --- a/apps/rigidShapes/MyWindow.cpp +++ b/apps/rigidShapes/MyWindow.cpp @@ -64,12 +64,12 @@ void MyWindow::timeStepping() } //============================================================================== -void MyWindow::drawSkels() +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } //============================================================================== diff --git a/apps/rigidShapes/MyWindow.h b/apps/rigidShapes/MyWindow.h index 3bbfa44fdb849..f1fbb50f4bdf9 100644 --- a/apps/rigidShapes/MyWindow.h +++ b/apps/rigidShapes/MyWindow.h @@ -62,7 +62,7 @@ class MyWindow : public dart::gui::SimWindow virtual void keyboard(unsigned char key, int x, int y) override; // Documentation inherited - virtual void drawSkels() override; + virtual void drawWorld() const override; /// Spawn a box into the world void spawnBox( diff --git a/apps/softBodies/MyWindow.cpp b/apps/softBodies/MyWindow.cpp index 49873264ab151..297ef081c194e 100644 --- a/apps/softBodies/MyWindow.cpp +++ b/apps/softBodies/MyWindow.cpp @@ -76,13 +76,13 @@ void MyWindow::timeStepping() mForceOnVertex /= 2.0; } -void MyWindow::drawSkels() +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); Eigen::Vector4d color; color << 0.5, 0.8, 0.6, 1.0; - mWorld->getSkeleton(0)->draw(mRI, color, false); + drawSkeleton(mWorld->getSkeleton(0).get(), color, false); // draw arrow if (mImpulseDuration > 0) @@ -98,7 +98,7 @@ void MyWindow::drawSkels() dart::gui::drawArrow3D(start, mForceOnRigidBody, len, 0.025, 0.05); } - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void MyWindow::keyboard(unsigned char key, int x, int y) diff --git a/apps/softBodies/MyWindow.h b/apps/softBodies/MyWindow.h index 70393057666f5..033c0d03c66d7 100644 --- a/apps/softBodies/MyWindow.h +++ b/apps/softBodies/MyWindow.h @@ -62,7 +62,7 @@ class MyWindow : public dart::gui::SoftSimWindow virtual void keyboard(unsigned char key, int x, int y); /// \brief - virtual void drawSkels(); + virtual void drawWorld() const; private: /// \brief diff --git a/apps/vehicle/MyWindow.cpp b/apps/vehicle/MyWindow.cpp index c47674333abc4..d29ae35de6e80 100644 --- a/apps/vehicle/MyWindow.cpp +++ b/apps/vehicle/MyWindow.cpp @@ -69,11 +69,11 @@ void MyWindow::timeStepping() { mWorld->step(); } -void MyWindow::drawSkels() { +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void MyWindow::keyboard(unsigned char _key, int _x, int _y) { diff --git a/apps/vehicle/MyWindow.h b/apps/vehicle/MyWindow.h index 893daeb88cfa4..cc25b1631a1e1 100644 --- a/apps/vehicle/MyWindow.h +++ b/apps/vehicle/MyWindow.h @@ -53,7 +53,7 @@ class MyWindow : public dart::gui::SimWindow { virtual void timeStepping(); /// \brief - virtual void drawSkels(); + virtual void drawWorld() const; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/dart/dynamics/BodyNode.cpp b/dart/dynamics/BodyNode.cpp index 1591aa148b283..a4bca701edfd2 100644 --- a/dart/dynamics/BodyNode.cpp +++ b/dart/dynamics/BodyNode.cpp @@ -1379,6 +1379,8 @@ void BodyNode::draw(renderer::RenderInterface* ri, const Eigen::Vector4d& color, bool useDefaultColor, int /*depth*/) const { + DART_SUPPRESS_DEPRECATED_BEGIN + if (nullptr == ri) return; @@ -1401,6 +1403,8 @@ void BodyNode::draw(renderer::RenderInterface* ri, entity->draw(ri, color, useDefaultColor); ri->popMatrix(); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== @@ -1408,6 +1412,8 @@ void BodyNode::drawMarkers(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, bool _useDefaultColor) const { + DART_SUPPRESS_DEPRECATED_BEGIN + if (!_ri) return; @@ -1423,6 +1429,8 @@ void BodyNode::drawMarkers(renderer::RenderInterface* _ri, mChildBodyNodes[i]->drawMarkers(_ri, _color, _useDefaultColor); _ri->popMatrix(); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/dynamics/BodyNode.h b/dart/dynamics/BodyNode.h index bcadf0a526e62..537e053fb1d98 100644 --- a/dart/dynamics/BodyNode.h +++ b/dart/dynamics/BodyNode.h @@ -820,12 +820,14 @@ class BodyNode : //---------------------------------------------------------------------------- /// Render the markers + DEPRECATED(6.0) void draw(renderer::RenderInterface* ri = nullptr, const Eigen::Vector4d& color = Eigen::Vector4d::Ones(), bool useDefaultColor = true, int depth = 0) const override; /// Render the markers + DEPRECATED(6.0) void drawMarkers(renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), bool _useDefaultColor = true) const; diff --git a/dart/dynamics/BoxShape.h b/dart/dynamics/BoxShape.h index 721cbf9f2cc90..ed42ce1cc0dfc 100644 --- a/dart/dynamics/BoxShape.h +++ b/dart/dynamics/BoxShape.h @@ -58,6 +58,7 @@ class BoxShape : public Shape { const Eigen::Vector3d& getSize() const; // Documentation inherited. + DEPRECATED(6.0) void draw( renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _col = Eigen::Vector4d::Ones()) const override; diff --git a/dart/dynamics/CylinderShape.h b/dart/dynamics/CylinderShape.h index 90da2069257b4..99431dbd89d37 100644 --- a/dart/dynamics/CylinderShape.h +++ b/dart/dynamics/CylinderShape.h @@ -63,6 +63,7 @@ class CylinderShape : public Shape { void setHeight(double _height); // Documentation inherited. + DEPRECATED(6.0) void draw( renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones()) const override; diff --git a/dart/dynamics/EllipsoidShape.h b/dart/dynamics/EllipsoidShape.h index b5156b7555a66..6e8cef2005974 100644 --- a/dart/dynamics/EllipsoidShape.h +++ b/dart/dynamics/EllipsoidShape.h @@ -58,6 +58,7 @@ class EllipsoidShape : public Shape { const Eigen::Vector3d& getSize() const; // Documentation inherited. + DEPRECATED(6.0) void draw( renderer::RenderInterface* ri = nullptr, const Eigen::Vector4d& col = Eigen::Vector4d::Ones()) const override; diff --git a/dart/dynamics/Entity.h b/dart/dynamics/Entity.h index 205b3f646088e..f9a4c3eecceb0 100644 --- a/dart/dynamics/Entity.h +++ b/dart/dynamics/Entity.h @@ -126,6 +126,7 @@ class Entity : public virtual common::Subject virtual const std::string& getName() const; /// Render this Entity + DEPRECATED(6.0) virtual void draw(renderer::RenderInterface* ri = nullptr, const Eigen::Vector4d& color = Eigen::Vector4d::Ones(), bool useDefaultColor = true, diff --git a/dart/dynamics/Frame.cpp b/dart/dynamics/Frame.cpp index 7938841f89198..e2d3e10fd6eaa 100644 --- a/dart/dynamics/Frame.cpp +++ b/dart/dynamics/Frame.cpp @@ -443,6 +443,8 @@ bool Frame::isWorld() const void Frame::draw(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, bool _useDefaultColor, int _depth) const { + DART_SUPPRESS_DEPRECATED_BEGIN + if(nullptr == _ri) return; @@ -461,6 +463,8 @@ void Frame::draw(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, entity->draw(_ri, _color, _useDefaultColor); _ri->popMatrix(); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/dynamics/Frame.h b/dart/dynamics/Frame.h index ceed644258338..1df82b641202d 100644 --- a/dart/dynamics/Frame.h +++ b/dart/dynamics/Frame.h @@ -240,6 +240,7 @@ class Frame : public virtual Entity //-------------------------------------------------------------------------- // Render this Frame as well as any Entities it contains + DEPRECATED(6.0) void draw( renderer::RenderInterface *_ri = nullptr, const Eigen::Vector4d &_color = Eigen::Vector4d::Ones(), diff --git a/dart/dynamics/LineSegmentShape.h b/dart/dynamics/LineSegmentShape.h index 2ffe4e0b14da7..965cd0123f0f3 100644 --- a/dart/dynamics/LineSegmentShape.h +++ b/dart/dynamics/LineSegmentShape.h @@ -101,6 +101,7 @@ class LineSegmentShape : public Shape const Eigen::aligned_vector& getConnections() const; // Documentation inherited + DEPRECATED(6.0) virtual void draw(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color) const override; diff --git a/dart/dynamics/Marker.cpp b/dart/dynamics/Marker.cpp index ca8f52ee6e735..d6bb2f855cdc9 100644 --- a/dart/dynamics/Marker.cpp +++ b/dart/dynamics/Marker.cpp @@ -196,6 +196,12 @@ Marker::ConstraintType Marker::getConstraintType() const return mProperties.mType; } +//============================================================================== +const Eigen::Vector4d& Marker::getColor() const +{ + return mProperties.mColor; +} + //============================================================================== Marker::Marker(const Properties& properties, BodyNode* parent) : mProperties(properties), diff --git a/dart/dynamics/Marker.h b/dart/dynamics/Marker.h index 51869f26cd05a..da89b86cbc22a 100644 --- a/dart/dynamics/Marker.h +++ b/dart/dynamics/Marker.h @@ -90,6 +90,7 @@ class Marker virtual ~Marker(); /// Render this marker + DEPRECATED(6.0) void draw(renderer::RenderInterface* ri = nullptr, bool offset = true, const Eigen::Vector4d& color = Color::White(1.0), @@ -137,6 +138,9 @@ class Marker /// Get constraint type. which will be useful for inverse kinematics ConstraintType getConstraintType() const; + /// Return color of this Marker + const Eigen::Vector4d& getColor() const; + friend class Skeleton; friend class BodyNode; diff --git a/dart/dynamics/MeshShape.h b/dart/dynamics/MeshShape.h index c19ad62e2e49a..f66400e1b9144 100644 --- a/dart/dynamics/MeshShape.h +++ b/dart/dynamics/MeshShape.h @@ -127,6 +127,7 @@ class MeshShape : public Shape { void setDisplayList(int _index); // Documentation inherited. + DEPRECATED(6.0) void draw( renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _col = Eigen::Vector4d::Ones()) const override; diff --git a/dart/dynamics/PlaneShape.h b/dart/dynamics/PlaneShape.h index 81d31d74812de..17a3e5770abb0 100644 --- a/dart/dynamics/PlaneShape.h +++ b/dart/dynamics/PlaneShape.h @@ -53,7 +53,7 @@ class PlaneShape : public Shape PlaneShape(const Eigen::Vector3d& _normal, const Eigen::Vector3d& _point); // Documentation inherited. - // TODO(JS): Not implemented yet + DEPRECATED(6.0) void draw( renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _col = Eigen::Vector4d::Ones()) const override; diff --git a/dart/dynamics/PointMass.cpp b/dart/dynamics/PointMass.cpp index cfe4dfb9ab0ad..190e8227a5067 100644 --- a/dart/dynamics/PointMass.cpp +++ b/dart/dynamics/PointMass.cpp @@ -124,8 +124,7 @@ PointMass::PointMass(SoftBodyNode* _softBodyNode) mImpAlpha(Eigen::Vector3d::Zero()), mImpBeta(Eigen::Vector3d::Zero()), mImpF(Eigen::Vector3d::Zero()), - mNotifier(_softBodyNode->mNotifier), - mShape(new EllipsoidShape(Eigen::Vector3d(0.01, 0.01, 0.01))) + mNotifier(_softBodyNode->mNotifier) { assert(mParentSoftBodyNode != nullptr); mNotifier->notifyTransformUpdate(); @@ -134,7 +133,7 @@ PointMass::PointMass(SoftBodyNode* _softBodyNode) //============================================================================== PointMass::~PointMass() { - delete mShape; + // Do nothing } //============================================================================== @@ -1020,34 +1019,39 @@ void PointMass::aggregateExternalForces(VectorXd& /*_Fext*/) //============================================================================== void PointMass::draw(renderer::RenderInterface* _ri, - const Eigen::Vector4d& /*_color*/, - bool /*_useDefaultColor*/) const + const Eigen::Vector4d& _color, + bool _useDefaultColor) const { + DART_SUPPRESS_DEPRECATED_BEGIN + if (_ri == nullptr) return; - _ri->pushMatrix(); - - // render the self geometry - // mParentJoint->applyGLTransform(_ri); Eigen::Isometry3d T = Eigen::Isometry3d::Identity(); + + // render point at the current position + _ri->pushMatrix(); T.translation() = getLocalPosition(); _ri->transform(T); - Eigen::Vector4d color1; - color1 << 0.8, 0.3, 0.3, 1.0; - mShape->draw(_ri, color1); + if (_useDefaultColor) + _ri->setPenColor(Eigen::Vector4d(0.8, 0.3, 0.3, 1.0)); + else + _ri->setPenColor(_color); + _ri->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); _ri->popMatrix(); - // _ri->pushName((unsigned)mID); + // render point at the resting position _ri->pushMatrix(); T.translation() = getRestingPosition(); _ri->transform(T); - Eigen::Vector4d color2; - color2 << 0.3, 0.8, 0.3, 1.0; - mShape->draw(_ri, color2); + if (_useDefaultColor) + _ri->setPenColor(Eigen::Vector4d(0.3, 0.8, 0.3, 1.0)); + else + _ri->setPenColor(_color); + _ri->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); _ri->popMatrix(); - // _ri->popName(); + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/dynamics/PointMass.h b/dart/dynamics/PointMass.h index 22ad4859ad0e2..9e7d4cd5f09e2 100644 --- a/dart/dynamics/PointMass.h +++ b/dart/dynamics/PointMass.h @@ -509,7 +509,7 @@ class PointMass : public common::Subject Eigen::Vector3d mCg_F; //---------------------------- Rendering ------------------------------------- - /// + DEPRECATED(6.0) virtual void draw(renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), bool _useDefaultColor = true) const; @@ -647,9 +647,6 @@ class PointMass : public common::Subject PointMassNotifier* mNotifier; -private: - EllipsoidShape* mShape; - public: // To get byte-aligned Eigen vectors EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/dart/dynamics/Shape.h b/dart/dynamics/Shape.h index 201cc3935924b..e485a6467193c 100644 --- a/dart/dynamics/Shape.h +++ b/dart/dynamics/Shape.h @@ -141,7 +141,7 @@ class Shape : public virtual common::Subject /// Notify that the color (rgba) of this shape has updated virtual void notifyColorUpdate(const Eigen::Vector4d& color); - /// \brief + DEPRECATED(6.0) virtual void draw( renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones()) const = 0; diff --git a/dart/dynamics/ShapeFrame.cpp b/dart/dynamics/ShapeFrame.cpp index 5518b43bb029f..a621e28daa7f0 100644 --- a/dart/dynamics/ShapeFrame.cpp +++ b/dart/dynamics/ShapeFrame.cpp @@ -284,6 +284,8 @@ void ShapeFrame::draw(renderer::RenderInterface* ri, const Eigen::Vector4d& color, bool useDefaultColor) const { + DART_SUPPRESS_DEPRECATED_BEGIN + auto visualAddon = getVisualAddon(); if (!visualAddon || visualAddon->isHidden()) @@ -298,6 +300,8 @@ void ShapeFrame::draw(renderer::RenderInterface* ri, mShapeFrameP.mShape->draw(ri, color); ri->popMatrix(); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/dynamics/ShapeFrame.h b/dart/dynamics/ShapeFrame.h index 52b879dbe3a3f..4a2ed5f0d6c2c 100644 --- a/dart/dynamics/ShapeFrame.h +++ b/dart/dynamics/ShapeFrame.h @@ -304,6 +304,7 @@ class ShapeFrame : DART_BAKE_SPECIALIZED_ADDON(DynamicsAddon) /// Render this Entity + DEPRECATED(6.0) virtual void draw(renderer::RenderInterface* ri = nullptr, const Eigen::Vector4d& color = Eigen::Vector4d::Ones(), bool useDefaultColor = true) const; diff --git a/dart/dynamics/Skeleton.cpp b/dart/dynamics/Skeleton.cpp index 659efc54d6a7e..9c1e9c94113ec 100644 --- a/dart/dynamics/Skeleton.cpp +++ b/dart/dynamics/Skeleton.cpp @@ -1791,8 +1791,12 @@ const Eigen::VectorXd& Skeleton::getConstraintForces() const void Skeleton::draw(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, bool _useDefaultColor) const { + DART_SUPPRESS_DEPRECATED_BEGIN + for(size_t i=0; idraw(_ri, _color, _useDefaultColor); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== @@ -1800,7 +1804,11 @@ void Skeleton::drawMarkers(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, bool _useDefaultColor) const { + DART_SUPPRESS_DEPRECATED_BEGIN + getRootBodyNode()->drawMarkers(_ri, _color, _useDefaultColor); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/dynamics/Skeleton.h b/dart/dynamics/Skeleton.h index 3f4e598fe57bc..eb47d738b811f 100644 --- a/dart/dynamics/Skeleton.h +++ b/dart/dynamics/Skeleton.h @@ -953,11 +953,15 @@ class Skeleton : //---------------------------------------------------------------------------- /// Draw this skeleton + DEPRECATED(6.0) void draw(renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), bool _useDefaultColor = true) const; + // TODO(JS): Once this function is removed (e.g., at KIDO 7 or later), the + // dependency of renderer namespace can be removed from dynamics namespace. /// Draw markers in this skeleton + DEPRECATED(6.0) void drawMarkers(renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), bool _useDefaultColor = true) const; diff --git a/dart/dynamics/SoftBodyNode.cpp b/dart/dynamics/SoftBodyNode.cpp index de0b9e62df4c0..2aaea7d819838 100644 --- a/dart/dynamics/SoftBodyNode.cpp +++ b/dart/dynamics/SoftBodyNode.cpp @@ -255,6 +255,12 @@ const PointMass* SoftBodyNode::getPointMass(size_t _idx) const return const_cast(this)->getPointMass(_idx); } +//============================================================================== +const std::vector& SoftBodyNode::getPointMasses() const +{ + return mPointMasses; +} + //============================================================================== SoftBodyNode::SoftBodyNode(BodyNode* _parentBodyNode, Joint* _parentJoint, @@ -1143,6 +1149,8 @@ void SoftBodyNode::draw(renderer::RenderInterface* _ri, bool _useDefaultColor, int /*_depth*/) const { + DART_SUPPRESS_DEPRECATED_BEGIN + if (_ri == nullptr) return; @@ -1213,6 +1221,8 @@ void SoftBodyNode::draw(renderer::RenderInterface* _ri, entity->draw(_ri, _color, _useDefaultColor); _ri->popMatrix(); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/dynamics/SoftBodyNode.h b/dart/dynamics/SoftBodyNode.h index ffd3a8aa04865..0f37ccbf6fb44 100644 --- a/dart/dynamics/SoftBodyNode.h +++ b/dart/dynamics/SoftBodyNode.h @@ -183,6 +183,9 @@ class SoftBodyNode : public BodyNode /// \brief const PointMass* getPointMass(size_t _idx) const; + /// Return all the point masses in this SoftBodyNode + const std::vector& getPointMasses() const; + /// \brief void connectPointMasses(size_t _idx1, size_t _idx2); @@ -341,6 +344,7 @@ class SoftBodyNode : public BodyNode // Rendering //-------------------------------------------------------------------------- /// \brief Render the entire subtree rooted at this body node. + DEPRECATED(6.0) virtual void draw(renderer::RenderInterface* _ri = nullptr, const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), bool _useDefaultColor = true, int _depth = 0) const override; diff --git a/dart/dynamics/SoftMeshShape.h b/dart/dynamics/SoftMeshShape.h index eea133f8e3195..c737870f581b3 100644 --- a/dart/dynamics/SoftMeshShape.h +++ b/dart/dynamics/SoftMeshShape.h @@ -69,6 +69,7 @@ class SoftMeshShape : public Shape Eigen::Matrix3d computeInertia(double mass) const override; // Documentation inherited. + DEPRECATED(6.0) void draw( renderer::RenderInterface* ri = nullptr, const Eigen::Vector4d& col = Eigen::Vector4d::Ones()) const override; diff --git a/dart/gui/SimWindow.cpp b/dart/gui/SimWindow.cpp index 363d84a1175b1..0e4b07c9ae34e 100644 --- a/dart/gui/SimWindow.cpp +++ b/dart/gui/SimWindow.cpp @@ -47,12 +47,20 @@ #include "dart/simulation/World.h" #include "dart/dynamics/Skeleton.h" +#include "dart/dynamics/SoftBodyNode.h" +#include "dart/dynamics/BoxShape.h" +#include "dart/dynamics/EllipsoidShape.h" +#include "dart/dynamics/CylinderShape.h" +#include "dart/dynamics/PlaneShape.h" +#include "dart/dynamics/MeshShape.h" +#include "dart/dynamics/SoftMeshShape.h" +#include "dart/dynamics/LineSegmentShape.h" #include "dart/constraint/ConstraintSolver.h" #include "dart/collision/CollisionDetector.h" #include "dart/gui/LoadGlut.h" #include "dart/gui/GLFuncs.h" -#include "dart/utils/FileInfoWorld.h" #include "dart/gui/GraphWindow.h" +#include "dart/utils/FileInfoWorld.h" namespace dart { namespace gui { @@ -67,6 +75,7 @@ SimWindow::SimWindow() mPlay = false; mSimulating = false; mPlayFrame = 0; + mShowPointMasses = false; mShowMarkers = true; mPersp = 45.f; mTrans[1] = 300.f; @@ -82,21 +91,36 @@ void SimWindow::timeStepping() { } //============================================================================== -void SimWindow::drawSkels() +void SimWindow::drawWorld() const { - for (size_t i = 0; i < mWorld->getNumSkeletons(); ++i) - { - mWorld->getSkeleton(i)->draw(mRI); + drawSkeletons(); - if (mShowMarkers) - mWorld->getSkeleton(i)->drawMarkers(mRI); - } + for (auto i = 0u; i < mWorld->getNumSimpleFrames(); ++i) + drawShapeFrame(mWorld->getSimpleFrame(i).get()); +} + +//============================================================================== +void SimWindow::drawSkeletons() const +{ + for (auto i = 0u; i < mWorld->getNumSkeletons(); ++i) + drawSkeleton(mWorld->getSkeleton(i).get()); } +//============================================================================== +void SimWindow::drawSkels() +{ + drawSkeletons(); +} + +//============================================================================== void SimWindow::drawEntities() { + DART_SUPPRESS_DEPRECATED_BEGIN + for (size_t i = 0; i < mWorld->getNumSimpleFrames(); ++i) mWorld->getSimpleFrame(i)->draw(mRI); + + DART_SUPPRESS_DEPRECATED_END } void SimWindow::displayTimer(int _val) { @@ -164,8 +188,8 @@ void SimWindow::draw() { } } } - drawSkels(); - drawEntities(); + + drawWorld(); // display the frame count in 2D text char buff[64]; @@ -250,5 +274,278 @@ void SimWindow::plot(Eigen::VectorXd& _data) { mGraphWindows.push_back(figure); } +//============================================================================== +void SimWindow::drawSkeleton(const dynamics::Skeleton* skeleton, + const Eigen::Vector4d& color, + bool useDefaultColor) const +{ + if (!skeleton) + return; + + for (auto i = 0u; i < skeleton->getNumTrees(); ++i) + drawBodyNode(skeleton->getRootBodyNode(i), color, useDefaultColor, true); +} + +//============================================================================== +void SimWindow::drawEntity(const dynamics::Entity* entity, + const Eigen::Vector4d& color, + bool useDefaultColor) const +{ + if (!entity) + return; + + const auto& bodyNode = dynamic_cast(entity); + if (bodyNode) + { + drawBodyNode(bodyNode, color, useDefaultColor, true); + return; + } + + const auto& shapeFrame = dynamic_cast(entity); + if (shapeFrame) + { + drawShapeFrame(shapeFrame, color, useDefaultColor); + return; + } +} + +//============================================================================== +void SimWindow::drawBodyNode(const dynamics::BodyNode* bodyNode, + const Eigen::Vector4d& color, + bool useDefaultColor, + bool recursive) const +{ + if (!bodyNode) + return; + + if (!mRI) + return; + + mRI->pushMatrix(); + + // Use the relative transform of this Frame. We assume that we are being + // called from the parent Frame's renderer. + // TODO(MXG): This can cause trouble if the draw function is originally called + // on an Entity or Frame which is not a child of the World Frame + mRI->transform(bodyNode->getRelativeTransform()); + + // _ri->pushName(???); TODO(MXG): What should we do about this for Frames? + auto shapeNodes = bodyNode->getShapeNodesWith(); + for (const auto& shapeNode : shapeNodes) + drawShapeFrame(shapeNode, color, useDefaultColor); + // _ri.popName(); + + if (mShowPointMasses) + { + const auto& softBodyNode + = dynamic_cast(bodyNode); + if (softBodyNode) + drawPointMasses(softBodyNode->getPointMasses(), color); + } + + if (mShowMarkers) + { + for (auto i = 0u; i < bodyNode->getNumMarkers(); ++i) + drawMarker(bodyNode->getMarker(i)); + } + + // render the subtree + if (recursive) + { + for (const auto& entity : bodyNode->getChildEntities()) + drawEntity(entity, color, useDefaultColor); + } + + mRI->popMatrix(); +} + +//============================================================================== +void SimWindow::drawShapeFrame(const dynamics::ShapeFrame* shapeFrame, + const Eigen::Vector4d& color, + bool useDefaultColor) const +{ + if (!shapeFrame) + return; + + if (!mRI) + return; + + const auto& visualAddon = shapeFrame->getVisualAddon(); + + if (!visualAddon || visualAddon->isHidden()) + return; + + mRI->pushMatrix(); + mRI->transform(shapeFrame->getRelativeTransform()); + + if (useDefaultColor) + drawShape(shapeFrame->getShape().get(), visualAddon->getRGBA()); + else + drawShape(shapeFrame->getShape().get(), color); + + mRI->popMatrix(); +} + +//============================================================================== +void SimWindow::drawShape(const dynamics::Shape* shape, + const Eigen::Vector4d& color) const +{ + if (!shape) + return; + + if (!mRI) + return; + + glColorMaterial(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE); + glEnable(GL_COLOR_MATERIAL); + + mRI->setPenColor(color); + + using dynamics::Shape; + using dynamics::BoxShape; + using dynamics::EllipsoidShape; + using dynamics::CylinderShape; + using dynamics::PlaneShape; + using dynamics::MeshShape; + using dynamics::SoftMeshShape; + using dynamics::LineSegmentShape; + + switch (shape->getShapeType()) + { + case Shape::BOX: + { + const auto& box = static_cast(shape); + mRI->drawCube(box->getSize()); + + break; + } + case Shape::ELLIPSOID: + { + const auto& ellipsoid = static_cast(shape); + mRI->drawEllipsoid(ellipsoid->getSize()); + + break; + } + case Shape::CYLINDER: + { + const auto& cylinder = static_cast(shape); + mRI->drawCylinder(cylinder->getRadius(), cylinder->getHeight()); + + break; + } + case Shape::MESH: + { + const auto& mesh = static_cast(shape); + + glDisable(GL_COLOR_MATERIAL); // Use mesh colors to draw + + if (mesh->getDisplayList()) + mRI->drawList(mesh->getDisplayList()); + else + mRI->drawMesh(mesh->getScale(), mesh->getMesh()); + + break; + } + case Shape::SOFT_MESH: + { + const auto& softMesh = static_cast(shape); + mRI->drawSoftMesh(softMesh->getAssimpMesh()); + + break; + } + case Shape::LINE_SEGMENT: + { + const auto& lineSegmentShape + = static_cast(shape); + mRI->drawLineSegments(lineSegmentShape->getVertices(), + lineSegmentShape->getConnections()); + + break; + } + default: + { + dterr << "[SimWindow::drawShape] Attempting to draw unsupported shape " + << "type '" << shape->getShapeType() << "'.\n"; + break; + } + } + + glDisable(GL_COLOR_MATERIAL); +} + +//============================================================================== +void SimWindow::drawPointMasses( + const std::vector pointMasses, + const Eigen::Vector4d& color, + bool useDefaultColor) const +{ + if (!mRI) + return; + + for (const auto& pointMass : pointMasses) + { + Eigen::Isometry3d T = Eigen::Isometry3d::Identity(); + + // render point at the current position + mRI->pushMatrix(); + T.translation() = pointMass->getLocalPosition(); + mRI->transform(T); + if (useDefaultColor) + mRI->setPenColor(Eigen::Vector4d(0.8, 0.3, 0.3, 1.0)); + else + mRI->setPenColor(color); + mRI->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); + mRI->popMatrix(); + + // render point at the resting position + mRI->pushMatrix(); + T.translation() = pointMass->getRestingPosition(); + mRI->transform(T); + if (useDefaultColor) + mRI->setPenColor(Eigen::Vector4d(0.8, 0.3, 0.3, 1.0)); + else + mRI->setPenColor(color); + mRI->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); + mRI->popMatrix(); + } +} + +//============================================================================== +void SimWindow::drawMarker(const dynamics::Marker* marker, + const Eigen::Vector4d& color, + bool useDefaultColor) const +{ + if (!marker) + return; + + if (!mRI) + return; + + mRI->pushName(marker->getID()); + + if (marker->getConstraintType() == dynamics::Marker::HARD) + { + mRI->setPenColor(Color::Red(1.0)); + } + else if (marker->getConstraintType() == dynamics::Marker::SOFT) + { + mRI->setPenColor(Color::Green(1.0)); + } + else + { + if (useDefaultColor) + mRI->setPenColor(marker->getColor()); + else + mRI->setPenColor(color); + } + + mRI->pushMatrix(); + mRI->translate(marker->getLocalPosition()); + mRI->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); + mRI->popMatrix(); + + mRI->popName(); +} + } // namespace gui } // namespace dart diff --git a/dart/gui/SimWindow.h b/dart/gui/SimWindow.h index 5f89a392064bc..969198baf3ad9 100644 --- a/dart/gui/SimWindow.h +++ b/dart/gui/SimWindow.h @@ -66,10 +66,14 @@ class SimWindow : public Win3D { /// \brief virtual void timeStepping(); - /// \brief + virtual void drawWorld() const; + + virtual void drawSkeletons() const; + + DEPRECATED(6.0) virtual void drawSkels(); - /// \brief + DEPRECATED(6.0) virtual void drawEntities(); /// \brief @@ -94,6 +98,42 @@ class SimWindow : public Win3D { // void setSimulatingFlag(int _flag) { mSimulating = _flag; } protected: + + virtual void drawSkeleton( + const dynamics::Skeleton* skeleton, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5), + bool useDefaultColor = true) const; + + virtual void drawEntity( + const dynamics::Entity* entity, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5), + bool useDefaultColor = true) const; + + virtual void drawBodyNode( + const dynamics::BodyNode* bodyNode, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5), + bool useDefaultColor = true, + bool recursive = false) const; + + virtual void drawShapeFrame( + const dynamics::ShapeFrame* shapeFrame, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5), + bool useDefaultColor = true) const; + + virtual void drawShape( + const dynamics::Shape* shape, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5)) const; + + virtual void drawPointMasses( + const std::vector pointMasses, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5), + bool useDefaultColor = true) const; + + virtual void drawMarker( + const dynamics::Marker* marker, + const Eigen::Vector4d& color = Eigen::Vector4d::Constant(0.5), + bool useDefaultColor = true) const; + /// \brief simulation::WorldPtr mWorld; @@ -106,7 +146,10 @@ class SimWindow : public Win3D { /// \brief bool mSimulating; - /// \brief + /// If true, render point masses of soft bodies + bool mShowPointMasses; + + /// If true, render markers bool mShowMarkers; /// \brief Array of graph windows diff --git a/dart/renderer/OpenGLRenderInterface.cpp b/dart/renderer/OpenGLRenderInterface.cpp index f2e1e5ba9abd7..e1271ce45dcba 100644 --- a/dart/renderer/OpenGLRenderInterface.cpp +++ b/dart/renderer/OpenGLRenderInterface.cpp @@ -377,31 +377,70 @@ void OpenGLRenderInterface::recursiveRender(const struct aiScene *sc, const stru glPopMatrix(); } -void OpenGLRenderInterface::drawMesh(const Eigen::Vector3d& _scale, const aiScene* _mesh) { - if(_mesh) { - glPushMatrix(); - glScaled(_scale(0), _scale(1), _scale(2)); - recursiveRender(_mesh, _mesh->mRootNode); - glPopMatrix(); +//============================================================================== +void OpenGLRenderInterface::drawMesh( + const Eigen::Vector3d& scale, const aiScene* mesh) +{ + if (!mesh) + return; + + glPushMatrix(); + + glScaled(scale[0], scale[1], scale[2]); + recursiveRender(mesh, mesh->mRootNode); + + glPopMatrix(); +} + +//============================================================================== +void OpenGLRenderInterface::drawSoftMesh(const aiMesh* mesh) +{ + glEnable(GL_LIGHTING); + glEnable(GL_AUTO_NORMAL); + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); + + for (auto i = 0u; i < mesh->mNumFaces; ++i) + { + glBegin(GL_TRIANGLES); + + const auto& face = &mesh->mFaces[i]; + assert(3u == face->mNumIndices); + + for (auto j = 0u; j < 3; ++j) + { + auto index = face->mIndices[j]; + glNormal3fv(&mesh->mVertices[index].x); + glVertex3fv(&mesh->mVertices[index].x); } + + glEnd(); + } } void OpenGLRenderInterface::drawList(GLuint index) { glCallList(index); } -void OpenGLRenderInterface::compileList(dynamics::Skeleton* _skel) { - if(_skel == 0) - return; +//============================================================================== +void OpenGLRenderInterface::compileList(dynamics::Skeleton* _skel) +{ + DART_SUPPRESS_DEPRECATED_BEGIN - for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) { - compileList(_skel->getBodyNode(i)); - } + if(_skel == 0) + return; + + for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) { + compileList(_skel->getBodyNode(i)); + } + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== void OpenGLRenderInterface::compileList(dynamics::BodyNode* node) { + DART_SUPPRESS_DEPRECATED_BEGIN + if(node == 0) return; @@ -417,8 +456,11 @@ void OpenGLRenderInterface::compileList(dynamics::BodyNode* node) auto shapeNode = node->getNode(i); compileList(shapeNode->getShape().get()); } + + DART_SUPPRESS_DEPRECATED_END } +//============================================================================== //FIXME: Use polymorphism instead of switch statements void OpenGLRenderInterface::compileList(dynamics::Shape* _shape) { if(_shape == 0) @@ -470,19 +512,27 @@ GLuint OpenGLRenderInterface::compileList(const Eigen::Vector3d& _scale, const a return index; } -void OpenGLRenderInterface::draw(dynamics::Skeleton* _skel, bool _vizCol, bool _colMesh) { - if(_skel == 0) - return; +//============================================================================== +void OpenGLRenderInterface::draw(dynamics::Skeleton* _skel, bool _vizCol, + bool _colMesh) +{ + DART_SUPPRESS_DEPRECATED_BEGIN - for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) { - draw(_skel->getBodyNode(i), _vizCol, _colMesh); - } + if(_skel == 0) + return; + + for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) + draw(_skel->getBodyNode(i), _vizCol, _colMesh); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== void OpenGLRenderInterface::draw(dynamics::BodyNode* node, bool vizCol, bool colMesh) { + DART_SUPPRESS_DEPRECATED_BEGIN + if(node == 0) return; @@ -527,6 +577,8 @@ void OpenGLRenderInterface::draw(dynamics::BodyNode* node, glEnable( GL_TEXTURE_2D ); glDisable(GL_COLOR_MATERIAL); glPopMatrix(); + + DART_SUPPRESS_DEPRECATED_END } //============================================================================== diff --git a/dart/renderer/OpenGLRenderInterface.h b/dart/renderer/OpenGLRenderInterface.h index b4197a959a539..0255ec964d294 100644 --- a/dart/renderer/OpenGLRenderInterface.h +++ b/dart/renderer/OpenGLRenderInterface.h @@ -39,7 +39,8 @@ #include #include -#include "RenderInterface.h" +#include "dart/common/Deprecated.h" +#include "dart/renderer/RenderInterface.h" #include "dart/renderer/LoadOpengl.h" namespace dart { @@ -80,20 +81,21 @@ class OpenGLRenderInterface : public RenderInterface { virtual void transform(const Eigen::Isometry3d& _transform) override; //glMultMatrix virtual void scale(const Eigen::Vector3d& _scale) override; //glScale - void compileList(dynamics::Skeleton* _skel); - void compileList(dynamics::BodyNode* _node); - void compileList(dynamics::Shape* _shape); + DEPRECATED(6.0) void compileList(dynamics::Skeleton* _skel); + DEPRECATED(6.0) void compileList(dynamics::BodyNode* _node); + DEPRECATED(6.0) void compileList(dynamics::Shape* _shape); GLuint compileList(const Eigen::Vector3d& _scale, const aiScene* _mesh); - virtual void draw(dynamics::Skeleton* _skel, bool _vizCol = false, bool _colMesh = false); - virtual void draw(dynamics::BodyNode* _node, bool _vizCol = false, bool _colMesh = false); - virtual void draw(dynamics::Shape* _shape); - virtual void draw(dynamics::ShapeFrame* shapeFrame); + DEPRECATED(6.0) virtual void draw(dynamics::Skeleton* _skel, bool _vizCol = false, bool _colMesh = false); + DEPRECATED(6.0) virtual void draw(dynamics::BodyNode* _node, bool _vizCol = false, bool _colMesh = false); + DEPRECATED(6.0) virtual void draw(dynamics::Shape* _shape); + DEPRECATED(6.0) virtual void draw(dynamics::ShapeFrame* shapeFrame); virtual void drawEllipsoid(const Eigen::Vector3d& _size) override; virtual void drawCube(const Eigen::Vector3d& _size) override; virtual void drawCylinder(double _radius, double _height) override; virtual void drawMesh(const Eigen::Vector3d& _scale, const aiScene* _mesh) override; + virtual void drawSoftMesh(const aiMesh* mesh); virtual void drawList(GLuint index) override; virtual void drawLineSegments(const std::vector& _vertices, const Eigen::aligned_vector& _connections) override; diff --git a/dart/renderer/RenderInterface.cpp b/dart/renderer/RenderInterface.cpp index bbbbe828f492b..22bdfbc1c4b48 100644 --- a/dart/renderer/RenderInterface.cpp +++ b/dart/renderer/RenderInterface.cpp @@ -114,6 +114,11 @@ void RenderInterface::drawMesh(const Eigen::Vector3d& /*_scale*/, const aiScene* { } +void RenderInterface::drawSoftMesh(const aiMesh* /*mesh*/) +{ + // Do nothing +} + void RenderInterface::drawList(unsigned int /*indeX*/) { } diff --git a/dart/renderer/RenderInterface.h b/dart/renderer/RenderInterface.h index 7c5e2c13ca82e..ac48bdb1a0f8f 100644 --- a/dart/renderer/RenderInterface.h +++ b/dart/renderer/RenderInterface.h @@ -99,6 +99,7 @@ class RenderInterface { virtual void drawCube(const Eigen::Vector3d& _size); virtual void drawCylinder(double _radius, double _height); virtual void drawMesh(const Eigen::Vector3d& _scale, const aiScene* _mesh); + virtual void drawSoftMesh(const aiMesh* mesh); virtual void drawList(unsigned int index); virtual void drawLineSegments(const std::vector& _vertices, const Eigen::aligned_vector& _connections); diff --git a/tutorials/tutorialCollisions-Finished.cpp b/tutorials/tutorialCollisions-Finished.cpp index 765775cb18a35..445f9be7103c5 100644 --- a/tutorials/tutorialCollisions-Finished.cpp +++ b/tutorials/tutorialCollisions-Finished.cpp @@ -170,13 +170,13 @@ class MyWindow : public dart::gui::SimWindow } } - void drawSkels() override + void drawWorld() const override { // Make sure lighting is turned on and that polygons get filled in glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void displayTimer(int _val) override diff --git a/tutorials/tutorialCollisions.cpp b/tutorials/tutorialCollisions.cpp index 4c33c8e8428df..41bbbdfdb3ce9 100644 --- a/tutorials/tutorialCollisions.cpp +++ b/tutorials/tutorialCollisions.cpp @@ -152,13 +152,13 @@ class MyWindow : public SimWindow } } - void drawSkels() override + void drawWorld() const override { // Make sure lighting is turned on and that polygons get filled in glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - SimWindow::drawSkels(); + SimWindow::drawWorld(); } void displayTimer(int _val) override From d949ca0a8ad023832deafa5a07196a520b34b97e Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 30 Mar 2016 20:41:07 -0400 Subject: [PATCH 2/3] Fix overriding of SimWindow::drawWorld() in apps --- apps/addDeleteSkels/MyWindow.h | 2 +- apps/bipedStand/MyWindow.cpp | 2 +- apps/bipedStand/MyWindow.h | 2 +- apps/hybridDynamics/MyWindow.h | 2 +- apps/mixedChain/MyWindow.cpp | 2 +- apps/mixedChain/MyWindow.h | 2 +- apps/operationalSpaceControl/MyWindow.cpp | 2 +- apps/operationalSpaceControl/MyWindow.h | 2 +- apps/rigidCubes/MyWindow.h | 2 +- apps/softBodies/MyWindow.h | 2 +- apps/vehicle/MyWindow.h | 2 +- 11 files changed, 11 insertions(+), 11 deletions(-) diff --git a/apps/addDeleteSkels/MyWindow.h b/apps/addDeleteSkels/MyWindow.h index 9cf17e572ec65..b605d57f63e5d 100644 --- a/apps/addDeleteSkels/MyWindow.h +++ b/apps/addDeleteSkels/MyWindow.h @@ -50,7 +50,7 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); /// \brief - virtual void drawWorld() const; + virtual void drawWorld() const override; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/bipedStand/MyWindow.cpp b/apps/bipedStand/MyWindow.cpp index b0bebba657b78..de0830a412cb2 100644 --- a/apps/bipedStand/MyWindow.cpp +++ b/apps/bipedStand/MyWindow.cpp @@ -62,7 +62,7 @@ void MyWindow::timeStepping() { } } -void MyWindow::drawWorld() { +void MyWindow::drawWorld() const { SimWindow::drawWorld(); diff --git a/apps/bipedStand/MyWindow.h b/apps/bipedStand/MyWindow.h index 284b3a1bb8e94..c9c94d77f3d1a 100644 --- a/apps/bipedStand/MyWindow.h +++ b/apps/bipedStand/MyWindow.h @@ -52,7 +52,7 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); virtual void timeStepping(); - virtual void drawWorld(); + virtual void drawWorld() const override; virtual void keyboard(unsigned char _key, int _x, int _y); void setController(Controller* _controller); diff --git a/apps/hybridDynamics/MyWindow.h b/apps/hybridDynamics/MyWindow.h index c065282cf9fa8..e8c800e95a254 100644 --- a/apps/hybridDynamics/MyWindow.h +++ b/apps/hybridDynamics/MyWindow.h @@ -53,7 +53,7 @@ class MyWindow : public dart::gui::SimWindow virtual void timeStepping(); /// \brief - virtual void drawWorld() const; + virtual void drawWorld() const override; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/mixedChain/MyWindow.cpp b/apps/mixedChain/MyWindow.cpp index ec22361dfe141..7aec0ed8b9cac 100644 --- a/apps/mixedChain/MyWindow.cpp +++ b/apps/mixedChain/MyWindow.cpp @@ -77,7 +77,7 @@ void MyWindow::timeStepping() mForceOnVertex /= 2.0; } -void MyWindow::drawWorld() +void MyWindow::drawWorld() const { glEnable(GL_LIGHTING); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); diff --git a/apps/mixedChain/MyWindow.h b/apps/mixedChain/MyWindow.h index 6e731bfd17b02..48c9a6161a650 100644 --- a/apps/mixedChain/MyWindow.h +++ b/apps/mixedChain/MyWindow.h @@ -62,7 +62,7 @@ class MyWindow : public dart::gui::SoftSimWindow virtual void keyboard(unsigned char key, int x, int y); /// \brief - virtual void drawWorld(); + virtual void drawWorld() const override; private: /// \brief diff --git a/apps/operationalSpaceControl/MyWindow.cpp b/apps/operationalSpaceControl/MyWindow.cpp index 50a368ead6338..44c2256aea232 100644 --- a/apps/operationalSpaceControl/MyWindow.cpp +++ b/apps/operationalSpaceControl/MyWindow.cpp @@ -81,7 +81,7 @@ void MyWindow::timeStepping() } //============================================================================== -void MyWindow::drawWorld() +void MyWindow::drawWorld() const { // Draw the target position if (mRI) diff --git a/apps/operationalSpaceControl/MyWindow.h b/apps/operationalSpaceControl/MyWindow.h index 334a501ab66e0..3dbeb616d48c8 100644 --- a/apps/operationalSpaceControl/MyWindow.h +++ b/apps/operationalSpaceControl/MyWindow.h @@ -55,7 +55,7 @@ class MyWindow : public dart::gui::SimWindow virtual void timeStepping(); // Documentation inherited - virtual void drawWorld(); + virtual void drawWorld() const override; // Documentation inherited virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/rigidCubes/MyWindow.h b/apps/rigidCubes/MyWindow.h index 140b4d6b5e672..254f34684fdfc 100644 --- a/apps/rigidCubes/MyWindow.h +++ b/apps/rigidCubes/MyWindow.h @@ -53,7 +53,7 @@ class MyWindow : public dart::gui::SimWindow { virtual void timeStepping(); /// \brief - virtual void drawWorld() const; + virtual void drawWorld() const override; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); diff --git a/apps/softBodies/MyWindow.h b/apps/softBodies/MyWindow.h index 033c0d03c66d7..df4ac092c7932 100644 --- a/apps/softBodies/MyWindow.h +++ b/apps/softBodies/MyWindow.h @@ -62,7 +62,7 @@ class MyWindow : public dart::gui::SoftSimWindow virtual void keyboard(unsigned char key, int x, int y); /// \brief - virtual void drawWorld() const; + virtual void drawWorld() const override; private: /// \brief diff --git a/apps/vehicle/MyWindow.h b/apps/vehicle/MyWindow.h index cc25b1631a1e1..6e73312342483 100644 --- a/apps/vehicle/MyWindow.h +++ b/apps/vehicle/MyWindow.h @@ -53,7 +53,7 @@ class MyWindow : public dart::gui::SimWindow { virtual void timeStepping(); /// \brief - virtual void drawWorld() const; + virtual void drawWorld() const override; /// \brief virtual void keyboard(unsigned char _key, int _x, int _y); From deffdcd008b9fccb919f412f49b567bfc3a9cc05 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sun, 3 Apr 2016 11:26:00 -0400 Subject: [PATCH 3/3] Remove draw functions from dynamics namespace --- .../fcl_mesh/FCLMeshCollisionDetector.cpp | 11 - .../fcl_mesh/FCLMeshCollisionDetector.h | 3 - .../fcl_mesh/FCLMeshCollisionNode.cpp | 36 --- .../collision/fcl_mesh/FCLMeshCollisionNode.h | 3 - dart/dynamics/BodyNode.cpp | 60 ---- dart/dynamics/BodyNode.h | 23 -- dart/dynamics/BoxShape.cpp | 12 - dart/dynamics/BoxShape.h | 6 - dart/dynamics/CylinderShape.cpp | 12 - dart/dynamics/CylinderShape.h | 6 - dart/dynamics/EllipsoidShape.cpp | 13 - dart/dynamics/EllipsoidShape.h | 6 - dart/dynamics/Entity.cpp | 11 - dart/dynamics/Entity.h | 13 - dart/dynamics/Frame.cpp | 32 +-- dart/dynamics/Frame.h | 11 - dart/dynamics/Joint.cpp | 7 - dart/dynamics/Joint.h | 13 - dart/dynamics/LineSegmentShape.cpp | 12 - dart/dynamics/LineSegmentShape.h | 5 - dart/dynamics/Marker.cpp | 43 --- dart/dynamics/Marker.h | 13 - dart/dynamics/MeshShape.cpp | 14 +- dart/dynamics/MeshShape.h | 6 - dart/dynamics/PlaneShape.cpp | 14 - dart/dynamics/PlaneShape.h | 6 - dart/dynamics/PointMass.cpp | 39 --- dart/dynamics/PointMass.h | 12 - dart/dynamics/Shape.h | 11 - dart/dynamics/ShapeFrame.cpp | 27 -- dart/dynamics/ShapeFrame.h | 6 - dart/dynamics/Skeleton.cpp | 24 -- dart/dynamics/Skeleton.h | 24 -- dart/dynamics/SoftBodyNode.cpp | 87 +----- dart/dynamics/SoftBodyNode.h | 9 - dart/dynamics/SoftMeshShape.cpp | 6 - dart/dynamics/SoftMeshShape.h | 6 - dart/gui/SimWindow.cpp | 6 +- dart/renderer/OpenGLRenderInterface.cpp | 270 ++---------------- dart/renderer/OpenGLRenderInterface.h | 11 +- 40 files changed, 25 insertions(+), 904 deletions(-) diff --git a/dart/collision/fcl_mesh/FCLMeshCollisionDetector.cpp b/dart/collision/fcl_mesh/FCLMeshCollisionDetector.cpp index 8a4cc4c500ab4..e873382054c0c 100644 --- a/dart/collision/fcl_mesh/FCLMeshCollisionDetector.cpp +++ b/dart/collision/fcl_mesh/FCLMeshCollisionDetector.cpp @@ -42,7 +42,6 @@ #include -#include "dart/renderer/LoadOpengl.h" #include "dart/math/Helpers.h" #include "dart/dynamics/BodyNode.h" #include "dart/dynamics/SoftBodyNode.h" @@ -140,15 +139,5 @@ bool FCLMeshCollisionDetector::detectCollision(CollisionNode* _node1, mNumMaxContacts); } -//============================================================================== -void FCLMeshCollisionDetector::draw() -{ - for (size_t i = 0; i < mCollisionNodes.size(); i++) - { - static_cast( - mCollisionNodes[i])->drawCollisionSkeletonNode(); - } -} - } // namespace collision } // namespace dart diff --git a/dart/collision/fcl_mesh/FCLMeshCollisionDetector.h b/dart/collision/fcl_mesh/FCLMeshCollisionDetector.h index 9b84564b20b56..94968ce104349 100644 --- a/dart/collision/fcl_mesh/FCLMeshCollisionDetector.h +++ b/dart/collision/fcl_mesh/FCLMeshCollisionDetector.h @@ -69,9 +69,6 @@ class FCLMeshCollisionDetector : public CollisionDetector // Documentation inherited virtual bool detectCollision(CollisionNode* _node1, CollisionNode* _node2, bool _calculateContactPoints); - - /// - void draw(); }; } // namespace collision diff --git a/dart/collision/fcl_mesh/FCLMeshCollisionNode.cpp b/dart/collision/fcl_mesh/FCLMeshCollisionNode.cpp index 8e96f655ab87b..e2c9db44ea26e 100644 --- a/dart/collision/fcl_mesh/FCLMeshCollisionNode.cpp +++ b/dart/collision/fcl_mesh/FCLMeshCollisionNode.cpp @@ -51,7 +51,6 @@ #include "dart/dynamics/EllipsoidShape.h" #include "dart/dynamics/CylinderShape.h" #include "dart/dynamics/SoftMeshShape.h" -#include "dart/renderer/LoadOpengl.h" #include "dart/collision/fcl_mesh/CollisionShapes.h" #include "dart/collision/fcl_mesh/FCLMeshCollisionDetector.h" @@ -432,41 +431,6 @@ int FCLMeshCollisionNode::evalContactPosition( return testRes; } -//============================================================================== -void FCLMeshCollisionNode::drawCollisionSkeletonNode(bool _bTrans) -{ - evalRT(); - double M[16]; - for (int i = 0; i < 4; i++) - for (int j = 0; j < 4; j++) - M[j * 4 + i] = mWorldTrans(i, j); -// fcl::Vec3f v1, v2, v3; - glPushMatrix(); - if (_bTrans) - glMultMatrixd(M); - glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); - glBegin(GL_TRIANGLES); - for (size_t i = 0; i < mMeshes.size(); i++) - { - for (int j = 0; j < mMeshes[i]->num_tris; j++) - { - fcl::Triangle tri = mMeshes[i]->tri_indices[j]; - glVertex3f(mMeshes[i]->vertices[tri[0]][0], - mMeshes[i]->vertices[tri[0]][1], - mMeshes[i]->vertices[tri[0]][2]); - glVertex3f(mMeshes[i]->vertices[tri[1]][0], - mMeshes[i]->vertices[tri[1]][1], - mMeshes[i]->vertices[tri[1]][2]); - glVertex3f(mMeshes[i]->vertices[tri[2]][0], - mMeshes[i]->vertices[tri[2]][1], - mMeshes[i]->vertices[tri[2]][2]); - } - } - glEnd(); - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - glPopMatrix(); -} - //============================================================================== template fcl::BVHModel* createSoftMesh(const aiMesh* _mesh, diff --git a/dart/collision/fcl_mesh/FCLMeshCollisionNode.h b/dart/collision/fcl_mesh/FCLMeshCollisionNode.h index 87d528684410b..a96482727cf24 100644 --- a/dart/collision/fcl_mesh/FCLMeshCollisionNode.h +++ b/dart/collision/fcl_mesh/FCLMeshCollisionNode.h @@ -102,9 +102,6 @@ class FCLMeshCollisionNode : public CollisionNode Eigen::Vector3d* _contactPosition1, Eigen::Vector3d* _contactPosition2); - /// - void drawCollisionSkeletonNode(bool _bTrans = true); - private: /// static int FFtest( diff --git a/dart/dynamics/BodyNode.cpp b/dart/dynamics/BodyNode.cpp index a4bca701edfd2..26f3c245117c1 100644 --- a/dart/dynamics/BodyNode.cpp +++ b/dart/dynamics/BodyNode.cpp @@ -44,7 +44,6 @@ #include "dart/common/Console.h" #include "dart/common/StlHelpers.h" #include "dart/math/Helpers.h" -#include "dart/renderer/RenderInterface.h" #include "dart/dynamics/Joint.h" #include "dart/dynamics/Shape.h" #include "dart/dynamics/Skeleton.h" @@ -1374,65 +1373,6 @@ void BodyNode::processRemovedEntity(Entity* _oldChildEntity) mNonBodyNodeEntities.erase(_oldChildEntity); } -//============================================================================== -void BodyNode::draw(renderer::RenderInterface* ri, - const Eigen::Vector4d& color, - bool useDefaultColor, int /*depth*/) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if (nullptr == ri) - return; - - ri->pushMatrix(); - - // Use the relative transform of this Frame. We assume that we are being - // called from the parent Frame's renderer. - // TODO(MXG): This can cause trouble if the draw function is originally called - // on an Entity or Frame which is not a child of the World Frame - ri->transform(getRelativeTransform()); - - // _ri->pushName(???); TODO(MXG): What should we do about this for Frames? - auto shapeNodes = getShapeNodesWith(); - for (auto shapeNode : shapeNodes) - shapeNode->draw(ri, color, useDefaultColor); - // _ri.popName(); - - // render the subtree - for(Entity* entity : mChildEntities) - entity->draw(ri, color, useDefaultColor); - - ri->popMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - -//============================================================================== -void BodyNode::drawMarkers(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color, - bool _useDefaultColor) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if (!_ri) - return; - - _ri->pushMatrix(); - - mParentJoint->applyGLTransform(_ri); - - // render the corresponding mMarkerss - for (size_t i = 0; i < mMarkers.size(); i++) - mMarkers[i]->draw(_ri, true, _color, _useDefaultColor); - - for (size_t i = 0; i < mChildBodyNodes.size(); i++) - mChildBodyNodes[i]->drawMarkers(_ri, _color, _useDefaultColor); - - _ri->popMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - //============================================================================== void BodyNode::notifyTransformUpdate() { diff --git a/dart/dynamics/BodyNode.h b/dart/dynamics/BodyNode.h index 537e053fb1d98..d5b9a8d574939 100644 --- a/dart/dynamics/BodyNode.h +++ b/dart/dynamics/BodyNode.h @@ -55,12 +55,6 @@ #include "dart/dynamics/detail/BodyNodeProperties.h" #include "dart/dynamics/Skeleton.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { @@ -815,23 +809,6 @@ class BodyNode : Eigen::Vector3d getAngularMomentum( const Eigen::Vector3d& _pivot = Eigen::Vector3d::Zero()); - //---------------------------------------------------------------------------- - // Rendering - //---------------------------------------------------------------------------- - - /// Render the markers - DEPRECATED(6.0) - void draw(renderer::RenderInterface* ri = nullptr, - const Eigen::Vector4d& color = Eigen::Vector4d::Ones(), - bool useDefaultColor = true, - int depth = 0) const override; - - /// Render the markers - DEPRECATED(6.0) - void drawMarkers(renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), - bool _useDefaultColor = true) const; - //---------------------------------------------------------------------------- // Notifications //---------------------------------------------------------------------------- diff --git a/dart/dynamics/BoxShape.cpp b/dart/dynamics/BoxShape.cpp index c3c7995cc4ab3..1a5a5d20026a7 100644 --- a/dart/dynamics/BoxShape.cpp +++ b/dart/dynamics/BoxShape.cpp @@ -37,7 +37,6 @@ #include #include "dart/dynamics/BoxShape.h" -#include "dart/renderer/RenderInterface.h" namespace dart { namespace dynamics { @@ -89,17 +88,6 @@ const Eigen::Vector3d& BoxShape::getSize() const { return mSize; } -//============================================================================== -void BoxShape::draw(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color) const -{ - if (!_ri) - return; - - _ri->setPenColor(_color); - _ri->drawCube(mBoundingBox.computeFullExtents()); -} - //============================================================================== Eigen::Matrix3d BoxShape::computeInertia(double mass) const { diff --git a/dart/dynamics/BoxShape.h b/dart/dynamics/BoxShape.h index ed42ce1cc0dfc..8e5b8cec2c36a 100644 --- a/dart/dynamics/BoxShape.h +++ b/dart/dynamics/BoxShape.h @@ -57,12 +57,6 @@ class BoxShape : public Shape { /// \brief Get size of this box. const Eigen::Vector3d& getSize() const; - // Documentation inherited. - DEPRECATED(6.0) - void draw( - renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _col = Eigen::Vector4d::Ones()) const override; - /// \brief Compute volume from given properties static double computeVolume(const Eigen::Vector3d& size); diff --git a/dart/dynamics/CylinderShape.cpp b/dart/dynamics/CylinderShape.cpp index 5ddb4a749eb1a..e80539a803aaa 100644 --- a/dart/dynamics/CylinderShape.cpp +++ b/dart/dynamics/CylinderShape.cpp @@ -36,7 +36,6 @@ #include #include "dart/dynamics/CylinderShape.h" -#include "dart/renderer/RenderInterface.h" namespace dart { namespace dynamics { @@ -73,17 +72,6 @@ void CylinderShape::setHeight(double _height) { updateVolume(); } -//============================================================================== -void CylinderShape::draw(renderer::RenderInterface* ri, - const Eigen::Vector4d& color) const -{ - if (!ri) - return; - - ri->setPenColor(color); - ri->drawCylinder(mRadius, mHeight); -} - //============================================================================== double CylinderShape::computeVolume(double radius, double height) { diff --git a/dart/dynamics/CylinderShape.h b/dart/dynamics/CylinderShape.h index 99431dbd89d37..4e502e957c11b 100644 --- a/dart/dynamics/CylinderShape.h +++ b/dart/dynamics/CylinderShape.h @@ -62,12 +62,6 @@ class CylinderShape : public Shape { /// \brief void setHeight(double _height); - // Documentation inherited. - DEPRECATED(6.0) - void draw( - renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones()) const override; - /// \brief Compute volume from given properties static double computeVolume(double radius, double height); diff --git a/dart/dynamics/EllipsoidShape.cpp b/dart/dynamics/EllipsoidShape.cpp index 6c6727a4fad4e..1142f28e68268 100644 --- a/dart/dynamics/EllipsoidShape.cpp +++ b/dart/dynamics/EllipsoidShape.cpp @@ -37,8 +37,6 @@ #include "dart/dynamics/EllipsoidShape.h" -#include "dart/renderer/RenderInterface.h" - namespace dart { namespace dynamics { @@ -64,17 +62,6 @@ const Eigen::Vector3d&EllipsoidShape::getSize() const { return mSize; } -//============================================================================== -void EllipsoidShape::draw(renderer::RenderInterface* ri, - const Eigen::Vector4d& col) const -{ - if (!ri) - return; - - ri->setPenColor(col); - ri->drawEllipsoid(mBoundingBox.computeFullExtents()); -} - //============================================================================== double EllipsoidShape::computeVolume(const Eigen::Vector3d& size) { diff --git a/dart/dynamics/EllipsoidShape.h b/dart/dynamics/EllipsoidShape.h index 6e8cef2005974..b77e3bf01def9 100644 --- a/dart/dynamics/EllipsoidShape.h +++ b/dart/dynamics/EllipsoidShape.h @@ -57,12 +57,6 @@ class EllipsoidShape : public Shape { /// \brief Get size of this box. const Eigen::Vector3d& getSize() const; - // Documentation inherited. - DEPRECATED(6.0) - void draw( - renderer::RenderInterface* ri = nullptr, - const Eigen::Vector4d& col = Eigen::Vector4d::Ones()) const override; - /// \brief Compute volume from given properties static double computeVolume(const Eigen::Vector3d& size); diff --git a/dart/dynamics/Entity.cpp b/dart/dynamics/Entity.cpp index b6829cc0cd6ae..3bdd1d8fc6cf0 100644 --- a/dart/dynamics/Entity.cpp +++ b/dart/dynamics/Entity.cpp @@ -41,8 +41,6 @@ #include "dart/dynamics/Frame.h" #include "dart/dynamics/Shape.h" -#include "dart/renderer/RenderInterface.h" - namespace dart { namespace dynamics { @@ -142,15 +140,6 @@ const std::string& Entity::getName() const return mEntityP.mName; } -//============================================================================== -void Entity::draw(renderer::RenderInterface* /*_ri*/, - const Eigen::Vector4d& /*_color*/, - bool /*_useDefaultColor*/, - int /*depth*/) const -{ - // Do nothing -} - //============================================================================== Frame* Entity::getParentFrame() { diff --git a/dart/dynamics/Entity.h b/dart/dynamics/Entity.h index f9a4c3eecceb0..4f78eccfb947d 100644 --- a/dart/dynamics/Entity.h +++ b/dart/dynamics/Entity.h @@ -47,12 +47,6 @@ #include "dart/dynamics/Shape.h" #include "dart/dynamics/SmartPointer.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { @@ -125,13 +119,6 @@ class Entity : public virtual common::Subject /// Return the name of this Entity virtual const std::string& getName() const; - /// Render this Entity - DEPRECATED(6.0) - virtual void draw(renderer::RenderInterface* ri = nullptr, - const Eigen::Vector4d& color = Eigen::Vector4d::Ones(), - bool useDefaultColor = true, - int depth = 0) const; - /// Get the parent (reference) frame of this Entity Frame* getParentFrame(); diff --git a/dart/dynamics/Frame.cpp b/dart/dynamics/Frame.cpp index e2d3e10fd6eaa..f17aa580869c8 100644 --- a/dart/dynamics/Frame.cpp +++ b/dart/dynamics/Frame.cpp @@ -35,9 +35,9 @@ */ #include "dart/dynamics/Frame.h" -#include "dart/dynamics/Shape.h" -#include "dart/renderer/RenderInterface.h" + #include "dart/common/Console.h" +#include "dart/dynamics/Shape.h" namespace dart { namespace dynamics { @@ -439,34 +439,6 @@ bool Frame::isWorld() const return mAmWorld; } -//============================================================================== -void Frame::draw(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, - bool _useDefaultColor, int _depth) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if(nullptr == _ri) - return; - - _ri->pushMatrix(); - - // Use the relative transform of this Frame. We assume that we are being - // called from the parent Frame's renderer. - // TODO(MXG): This can cause trouble if the draw function is originally called - // on an Entity or Frame which is not a child of the World Frame - _ri->transform(getRelativeTransform()); - - Entity::draw(_ri, _color, _useDefaultColor, _depth); - - // render the subtree - for(Entity* entity : mChildEntities) - entity->draw(_ri, _color, _useDefaultColor); - - _ri->popMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - //============================================================================== void Frame::notifyTransformUpdate() { diff --git a/dart/dynamics/Frame.h b/dart/dynamics/Frame.h index 1df82b641202d..47edd51376ee2 100644 --- a/dart/dynamics/Frame.h +++ b/dart/dynamics/Frame.h @@ -235,17 +235,6 @@ class Frame : public virtual Entity /// Returns true if this Frame is the World Frame bool isWorld() const; - //-------------------------------------------------------------------------- - // Rendering - //-------------------------------------------------------------------------- - - // Render this Frame as well as any Entities it contains - DEPRECATED(6.0) - void draw( - renderer::RenderInterface *_ri = nullptr, - const Eigen::Vector4d &_color = Eigen::Vector4d::Ones(), - bool _useDefaultColor = true, int _depth = 0) const override; - /// Notify this Frame and all its children that its pose has changed virtual void notifyTransformUpdate() override; diff --git a/dart/dynamics/Joint.cpp b/dart/dynamics/Joint.cpp index 610a22287787f..d487ee35090d9 100644 --- a/dart/dynamics/Joint.cpp +++ b/dart/dynamics/Joint.cpp @@ -41,7 +41,6 @@ #include "dart/common/Console.h" #include "dart/math/Helpers.h" -#include "dart/renderer/RenderInterface.h" #include "dart/dynamics/BodyNode.h" #include "dart/dynamics/DegreeOfFreedom.h" #include "dart/dynamics/Skeleton.h" @@ -435,12 +434,6 @@ const Eigen::Isometry3d& Joint::getTransformFromChildBodyNode() const return mJointP.mT_ChildBodyToJoint; } -//============================================================================== -void Joint::applyGLTransform(renderer::RenderInterface* _ri) -{ - _ri->transform(getLocalTransform()); -} - //============================================================================== Joint::Joint(const Properties& _properties) : mJointP(_properties), diff --git a/dart/dynamics/Joint.h b/dart/dynamics/Joint.h index f7601be2b4981..ca1b75f0ee5e3 100644 --- a/dart/dynamics/Joint.h +++ b/dart/dynamics/Joint.h @@ -49,12 +49,6 @@ #include "dart/math/MathTypes.h" #include "dart/dynamics/SmartPointer.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { @@ -719,13 +713,6 @@ class Joint : public virtual common::Subject, /// \} - //---------------------------------------------------------------------------- - // Rendering - //---------------------------------------------------------------------------- - - /// - void applyGLTransform(renderer::RenderInterface* _ri); - //---------------------------------------------------------------------------- // Friendship //---------------------------------------------------------------------------- diff --git a/dart/dynamics/LineSegmentShape.cpp b/dart/dynamics/LineSegmentShape.cpp index a63585c4a9cc2..67f489716bbde 100644 --- a/dart/dynamics/LineSegmentShape.cpp +++ b/dart/dynamics/LineSegmentShape.cpp @@ -36,7 +36,6 @@ #include "dart/dynamics/LineSegmentShape.h" #include "dart/common/Console.h" -#include "dart/renderer/RenderInterface.h" #include "dart/math/Geometry.h" namespace dart { @@ -276,17 +275,6 @@ LineSegmentShape::getConnections() const return mConnections; } -//============================================================================== -void LineSegmentShape::draw(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color) const -{ - if(!_ri) - return; - - _ri->setPenColor(_color); - _ri->drawLineSegments(mVertices, mConnections); -} - //============================================================================== Eigen::Matrix3d LineSegmentShape::computeInertia(double _mass) const { diff --git a/dart/dynamics/LineSegmentShape.h b/dart/dynamics/LineSegmentShape.h index 965cd0123f0f3..5cd4e40577712 100644 --- a/dart/dynamics/LineSegmentShape.h +++ b/dart/dynamics/LineSegmentShape.h @@ -100,11 +100,6 @@ class LineSegmentShape : public Shape /// Get all the connections const Eigen::aligned_vector& getConnections() const; - // Documentation inherited - DEPRECATED(6.0) - virtual void draw(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color) const override; - /// The returned inertia matrix will be like a very thin cylinder. The _mass /// will be evenly distributed across all lines. virtual Eigen::Matrix3d computeInertia(double mass) const override; diff --git a/dart/dynamics/Marker.cpp b/dart/dynamics/Marker.cpp index d6bb2f855cdc9..2c3c8f23ae3cf 100644 --- a/dart/dynamics/Marker.cpp +++ b/dart/dynamics/Marker.cpp @@ -39,7 +39,6 @@ #include #include "dart/dynamics/BodyNode.h" -#include "dart/renderer/RenderInterface.h" namespace dart { namespace dynamics { @@ -76,48 +75,6 @@ Marker::~Marker() // Do nothing } -//============================================================================== -void Marker::draw(renderer::RenderInterface* ri, - bool offset, - const Eigen::Vector4d& color, - bool useDefaultColor) const -{ - if (!ri) - return; - - ri->pushName(getID()); - - if (mProperties.mType == HARD) - { - ri->setPenColor(Color::Red(1.0)); - } - else if (mProperties.mType == SOFT) - { - ri->setPenColor(Color::Green(1.0)); - } - else - { - if (useDefaultColor) - ri->setPenColor(mProperties.mColor); - else - ri->setPenColor(color); - } - - if (offset) - { - ri->pushMatrix(); - ri->translate(mProperties.mOffset); - ri->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); - ri->popMatrix(); - } - else - { - ri->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); - } - - ri->popName(); -} - //============================================================================== BodyNode* Marker::getBodyNode() { diff --git a/dart/dynamics/Marker.h b/dart/dynamics/Marker.h index da89b86cbc22a..ae7f66147150e 100644 --- a/dart/dynamics/Marker.h +++ b/dart/dynamics/Marker.h @@ -41,12 +41,6 @@ #include #include "dart/math/Helpers.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { @@ -89,13 +83,6 @@ class Marker /// Destructor virtual ~Marker(); - /// Render this marker - DEPRECATED(6.0) - void draw(renderer::RenderInterface* ri = nullptr, - bool offset = true, - const Eigen::Vector4d& color = Color::White(1.0), - bool useDefaultColor = true) const; - /// Get the BodyNode this Marker belongs to BodyNode* getBodyNode(); diff --git a/dart/dynamics/MeshShape.cpp b/dart/dynamics/MeshShape.cpp index 33395305da302..ca102df1ebe21 100644 --- a/dart/dynamics/MeshShape.cpp +++ b/dart/dynamics/MeshShape.cpp @@ -45,11 +45,10 @@ #include #include "dart/config.h" -#include "dart/renderer/RenderInterface.h" #include "dart/common/Console.h" -#include "dart/dynamics/AssimpInputResourceAdaptor.h" #include "dart/common/LocalResourceRetriever.h" #include "dart/common/Uri.h" +#include "dart/dynamics/AssimpInputResourceAdaptor.h" #if !(ASSIMP_AISCENE_CTOR_DTOR_DEFINED) // We define our own constructor and destructor for aiScene, because it seems to @@ -258,17 +257,6 @@ void MeshShape::setDisplayList(int _index) { mDisplayList = _index; } -//============================================================================== -void MeshShape::draw(renderer::RenderInterface* ri, - const Eigen::Vector4d& color) const -{ - if (!ri) - return; - - ri->setPenColor(color); - ri->drawMesh(mScale, mMesh); -} - Eigen::Matrix3d MeshShape::computeInertia(double _mass) const { // use bounding box to represent the mesh Eigen::Vector3d bounds = mBoundingBox.computeFullExtents(); diff --git a/dart/dynamics/MeshShape.h b/dart/dynamics/MeshShape.h index f66400e1b9144..50b9c0d8927c5 100644 --- a/dart/dynamics/MeshShape.h +++ b/dart/dynamics/MeshShape.h @@ -126,12 +126,6 @@ class MeshShape : public Shape { /// \brief void setDisplayList(int _index); - // Documentation inherited. - DEPRECATED(6.0) - void draw( - renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _col = Eigen::Vector4d::Ones()) const override; - /// \brief static const aiScene* loadMesh(const std::string& _fileName); diff --git a/dart/dynamics/PlaneShape.cpp b/dart/dynamics/PlaneShape.cpp index 486dcb4476c76..dca92ca84e3af 100644 --- a/dart/dynamics/PlaneShape.cpp +++ b/dart/dynamics/PlaneShape.cpp @@ -36,8 +36,6 @@ #include "dart/dynamics/PlaneShape.h" -#include "dart/renderer/RenderInterface.h" - namespace dart { namespace dynamics { @@ -58,18 +56,6 @@ PlaneShape::PlaneShape(const Eigen::Vector3d& _normal, { } -//============================================================================== -void PlaneShape::draw(renderer::RenderInterface* ri, - const Eigen::Vector4d& color) const -{ - if (!ri) - return; - - ri->setPenColor(color); - // TODO(JS): Not implemented yet - // _ri->drawPlane(...); -} - //============================================================================== Eigen::Matrix3d PlaneShape::computeInertia(double /*mass*/) const { diff --git a/dart/dynamics/PlaneShape.h b/dart/dynamics/PlaneShape.h index 17a3e5770abb0..4966c7a3f7ed5 100644 --- a/dart/dynamics/PlaneShape.h +++ b/dart/dynamics/PlaneShape.h @@ -52,12 +52,6 @@ class PlaneShape : public Shape /// Constructor PlaneShape(const Eigen::Vector3d& _normal, const Eigen::Vector3d& _point); - // Documentation inherited. - DEPRECATED(6.0) - void draw( - renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _col = Eigen::Vector4d::Ones()) const override; - // Documentation inherited. Eigen::Matrix3d computeInertia(double mass) const override; diff --git a/dart/dynamics/PointMass.cpp b/dart/dynamics/PointMass.cpp index 190e8227a5067..9a622c1f625a5 100644 --- a/dart/dynamics/PointMass.cpp +++ b/dart/dynamics/PointMass.cpp @@ -40,8 +40,6 @@ #include "dart/math/Geometry.h" #include "dart/math/Helpers.h" #include "dart/dynamics/EllipsoidShape.h" -#include "dart/renderer/RenderInterface.h" - #include "dart/dynamics/SoftBodyNode.h" using namespace Eigen; @@ -1017,43 +1015,6 @@ void PointMass::aggregateExternalForces(VectorXd& /*_Fext*/) // _Fext->segment<3>(iStart) = mFext; } -//============================================================================== -void PointMass::draw(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color, - bool _useDefaultColor) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if (_ri == nullptr) - return; - - Eigen::Isometry3d T = Eigen::Isometry3d::Identity(); - - // render point at the current position - _ri->pushMatrix(); - T.translation() = getLocalPosition(); - _ri->transform(T); - if (_useDefaultColor) - _ri->setPenColor(Eigen::Vector4d(0.8, 0.3, 0.3, 1.0)); - else - _ri->setPenColor(_color); - _ri->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); - _ri->popMatrix(); - - // render point at the resting position - _ri->pushMatrix(); - T.translation() = getRestingPosition(); - _ri->transform(T); - if (_useDefaultColor) - _ri->setPenColor(Eigen::Vector4d(0.3, 0.8, 0.3, 1.0)); - else - _ri->setPenColor(_color); - _ri->drawEllipsoid(Eigen::Vector3d::Constant(0.01)); - _ri->popMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - //============================================================================== PointMassNotifier::PointMassNotifier(SoftBodyNode* _parentSoftBody, const std::string& _name) diff --git a/dart/dynamics/PointMass.h b/dart/dynamics/PointMass.h index 9e7d4cd5f09e2..6df83d7be6969 100644 --- a/dart/dynamics/PointMass.h +++ b/dart/dynamics/PointMass.h @@ -41,12 +41,6 @@ #include #include "dart/dynamics/Entity.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { @@ -508,12 +502,6 @@ class PointMass : public common::Subject /// Eigen::Vector3d mCg_F; - //---------------------------- Rendering ------------------------------------- - DEPRECATED(6.0) - virtual void draw(renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), - bool _useDefaultColor = true) const; - protected: // TODO(JS): Need? /// diff --git a/dart/dynamics/Shape.h b/dart/dynamics/Shape.h index e485a6467193c..4ecfa28299a32 100644 --- a/dart/dynamics/Shape.h +++ b/dart/dynamics/Shape.h @@ -48,12 +48,6 @@ #include "dart/dynamics/SmartPointer.h" #include "dart/common/Deprecated.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { /// \brief @@ -141,11 +135,6 @@ class Shape : public virtual common::Subject /// Notify that the color (rgba) of this shape has updated virtual void notifyColorUpdate(const Eigen::Vector4d& color); - DEPRECATED(6.0) - virtual void draw( - renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones()) const = 0; - protected: /// \brief Update volume diff --git a/dart/dynamics/ShapeFrame.cpp b/dart/dynamics/ShapeFrame.cpp index a621e28daa7f0..c1a4adbf11baa 100644 --- a/dart/dynamics/ShapeFrame.cpp +++ b/dart/dynamics/ShapeFrame.cpp @@ -36,8 +36,6 @@ #include "dart/dynamics/ShapeFrame.h" -#include "dart/renderer/OpenGLRenderInterface.h" - namespace dart { namespace dynamics { @@ -279,31 +277,6 @@ ConstShapePtr ShapeFrame::getShape() const return mShapeFrameP.mShape; } -//============================================================================== -void ShapeFrame::draw(renderer::RenderInterface* ri, - const Eigen::Vector4d& color, - bool useDefaultColor) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - auto visualAddon = getVisualAddon(); - - if (!visualAddon || visualAddon->isHidden()) - return; - - ri->pushMatrix(); - ri->transform(getRelativeTransform()); - - if (useDefaultColor) - mShapeFrameP.mShape->draw(ri, visualAddon->getRGBA()); - else - mShapeFrameP.mShape->draw(ri, color); - - ri->popMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - //============================================================================== size_t ShapeFrame::incrementVersion() { diff --git a/dart/dynamics/ShapeFrame.h b/dart/dynamics/ShapeFrame.h index 4a2ed5f0d6c2c..39d89aecb6ce7 100644 --- a/dart/dynamics/ShapeFrame.h +++ b/dart/dynamics/ShapeFrame.h @@ -303,12 +303,6 @@ class ShapeFrame : DART_BAKE_SPECIALIZED_ADDON(DynamicsAddon) - /// Render this Entity - DEPRECATED(6.0) - virtual void draw(renderer::RenderInterface* ri = nullptr, - const Eigen::Vector4d& color = Eigen::Vector4d::Ones(), - bool useDefaultColor = true) const; - // Documentation inherited size_t incrementVersion() override; diff --git a/dart/dynamics/Skeleton.cpp b/dart/dynamics/Skeleton.cpp index 9c1e9c94113ec..bf51486babab8 100644 --- a/dart/dynamics/Skeleton.cpp +++ b/dart/dynamics/Skeleton.cpp @@ -1787,30 +1787,6 @@ const Eigen::VectorXd& Skeleton::getConstraintForces() const // return mFd; //} -//============================================================================== -void Skeleton::draw(renderer::RenderInterface* _ri, const Eigen::Vector4d& _color, - bool _useDefaultColor) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - for(size_t i=0; idraw(_ri, _color, _useDefaultColor); - - DART_SUPPRESS_DEPRECATED_END -} - -//============================================================================== -void Skeleton::drawMarkers(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color, - bool _useDefaultColor) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - getRootBodyNode()->drawMarkers(_ri, _color, _useDefaultColor); - - DART_SUPPRESS_DEPRECATED_END -} - //============================================================================== Skeleton::Skeleton(const Properties& _properties) : mSkeletonP(""), diff --git a/dart/dynamics/Skeleton.h b/dart/dynamics/Skeleton.h index eb47d738b811f..569a1fb1b259e 100644 --- a/dart/dynamics/Skeleton.h +++ b/dart/dynamics/Skeleton.h @@ -50,12 +50,6 @@ #include "dart/dynamics/detail/BodyNodeProperties.h" #include "dart/dynamics/SpecializedNodeManager.h" -namespace dart { -namespace renderer { -class RenderInterface; -} // namespace renderer -} // namespace dart - namespace dart { namespace dynamics { @@ -948,24 +942,6 @@ class Skeleton : /// \} - //---------------------------------------------------------------------------- - // Rendering - //---------------------------------------------------------------------------- - - /// Draw this skeleton - DEPRECATED(6.0) - void draw(renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), - bool _useDefaultColor = true) const; - // TODO(JS): Once this function is removed (e.g., at KIDO 7 or later), the - // dependency of renderer namespace can be removed from dynamics namespace. - - /// Draw markers in this skeleton - DEPRECATED(6.0) - void drawMarkers(renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), - bool _useDefaultColor = true) const; - //---------------------------------------------------------------------------- // Friendship //---------------------------------------------------------------------------- diff --git a/dart/dynamics/SoftBodyNode.cpp b/dart/dynamics/SoftBodyNode.cpp index 2aaea7d819838..3e47a4e2f09f8 100644 --- a/dart/dynamics/SoftBodyNode.cpp +++ b/dart/dynamics/SoftBodyNode.cpp @@ -40,14 +40,11 @@ #include #include -#include "dart/math/Helpers.h" #include "dart/common/Console.h" +#include "dart/math/Helpers.h" #include "dart/dynamics/Joint.h" #include "dart/dynamics/Shape.h" #include "dart/dynamics/Skeleton.h" -#include "dart/renderer/LoadOpengl.h" -#include "dart/renderer/RenderInterface.h" - #include "dart/dynamics/PointMass.h" #include "dart/dynamics/SoftMeshShape.h" @@ -1143,88 +1140,6 @@ void SoftBodyNode::clearInternalForces() mPointMasses[i]->resetForces(); } -//============================================================================== -void SoftBodyNode::draw(renderer::RenderInterface* _ri, - const Eigen::Vector4d& _color, - bool _useDefaultColor, - int /*_depth*/) const -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if (_ri == nullptr) - return; - - _ri->pushMatrix(); - - // render the self geometry -// mParentJoint->applyGLTransform(_ri); - _ri->transform(getRelativeTransform()); - - _ri->pushName((unsigned)mID); - - auto shapeNodes = getShapeNodesWith(); - for (auto shapeNode : shapeNodes) - shapeNode->draw(_ri, _color, _useDefaultColor); - - // vertex -// if (_showPointMasses) -// { -// for (size_t i = 0; i < mPointMasses.size(); ++i) -// { -// _ri->pushMatrix(); -// mPointMasses[i]->draw(_ri, _color, _useDefaultColor); -// _ri->popMatrix(); -// } -// } - - // edges (mesh) -// Eigen::Vector4d fleshColor = _color; -// fleshColor[3] = 0.5; -// _ri->setPenColor(fleshColor); -// if (_showMeshs) - { - _ri->setPenColor(mSoftShapeNode.lock()->get()->getRGBA()); - glEnable(GL_LIGHTING); - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); - - Eigen::Vector3d pos; - Eigen::Vector3d pos_normalized; - for (size_t i = 0; i < mSoftP.mFaces.size(); ++i) - { - glEnable(GL_AUTO_NORMAL); - glBegin(GL_TRIANGLES); - - pos = mPointMasses[mSoftP.mFaces[i](0)]->getLocalPosition(); - pos_normalized = pos.normalized(); - glNormal3f(pos_normalized(0), pos_normalized(1), pos_normalized(2)); - glVertex3f(pos(0), pos(1), pos(2)); - pos = mPointMasses[mSoftP.mFaces[i](1)]->getLocalPosition(); - pos_normalized = pos.normalized(); - glNormal3f(pos_normalized(0), pos_normalized(1), pos_normalized(2)); - glVertex3f(pos(0), pos(1), pos(2)); - pos = mPointMasses[mSoftP.mFaces[i](2)]->getLocalPosition(); - pos_normalized = pos.normalized(); - glNormal3f(pos_normalized(0), pos_normalized(1), pos_normalized(2)); - glVertex3f(pos(0), pos(1), pos(2)); - glEnd(); - } - } - - _ri->popName(); - - // render the subtree -// for (unsigned int i = 0; i < mChildBodyNodes.size(); i++) -// { -// getChildBodyNode(i)->draw(_ri, _color, _useDefaultColor); -// } - for(Entity* entity : mChildEntities) - entity->draw(_ri, _color, _useDefaultColor); - - _ri->popMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - //============================================================================== void SoftBodyNode::_addPiToArtInertia(const Eigen::Vector3d& _p, double _Pi) const { diff --git a/dart/dynamics/SoftBodyNode.h b/dart/dynamics/SoftBodyNode.h index 0f37ccbf6fb44..cac06047f8b26 100644 --- a/dart/dynamics/SoftBodyNode.h +++ b/dart/dynamics/SoftBodyNode.h @@ -340,15 +340,6 @@ class SoftBodyNode : public BodyNode virtual void clearInternalForces() override; - //-------------------------------------------------------------------------- - // Rendering - //-------------------------------------------------------------------------- - /// \brief Render the entire subtree rooted at this body node. - DEPRECATED(6.0) - virtual void draw(renderer::RenderInterface* _ri = nullptr, - const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(), - bool _useDefaultColor = true, int _depth = 0) const override; - protected: /// \brief List of point masses composing deformable mesh. std::vector mPointMasses; diff --git a/dart/dynamics/SoftMeshShape.cpp b/dart/dynamics/SoftMeshShape.cpp index aceb0d2e1418a..f1c593f042e06 100644 --- a/dart/dynamics/SoftMeshShape.cpp +++ b/dart/dynamics/SoftMeshShape.cpp @@ -79,12 +79,6 @@ Eigen::Matrix3d SoftMeshShape::computeInertia(double /*mass*/) const return Eigen::Matrix3d::Zero(); } -void SoftMeshShape::draw(renderer::RenderInterface* /*ri*/, - const Eigen::Vector4d& /*col*/) const -{ - // TODO(JS): Not implemented. -} - void SoftMeshShape::updateVolume() { // TODO(JS): Not implemented. diff --git a/dart/dynamics/SoftMeshShape.h b/dart/dynamics/SoftMeshShape.h index c737870f581b3..ee9dad9a5f674 100644 --- a/dart/dynamics/SoftMeshShape.h +++ b/dart/dynamics/SoftMeshShape.h @@ -68,12 +68,6 @@ class SoftMeshShape : public Shape // Documentation inherited. Eigen::Matrix3d computeInertia(double mass) const override; - // Documentation inherited. - DEPRECATED(6.0) - void draw( - renderer::RenderInterface* ri = nullptr, - const Eigen::Vector4d& col = Eigen::Vector4d::Ones()) const override; - protected: // Documentation inherited. void updateVolume() override; diff --git a/dart/gui/SimWindow.cpp b/dart/gui/SimWindow.cpp index 0e4b07c9ae34e..0b4666e6f8017 100644 --- a/dart/gui/SimWindow.cpp +++ b/dart/gui/SimWindow.cpp @@ -115,12 +115,8 @@ void SimWindow::drawSkels() //============================================================================== void SimWindow::drawEntities() { - DART_SUPPRESS_DEPRECATED_BEGIN - for (size_t i = 0; i < mWorld->getNumSimpleFrames(); ++i) - mWorld->getSimpleFrame(i)->draw(mRI); - - DART_SUPPRESS_DEPRECATED_END + drawShapeFrame(mWorld->getSimpleFrame(i).get()); } void SimWindow::displayTimer(int _val) { diff --git a/dart/renderer/OpenGLRenderInterface.cpp b/dart/renderer/OpenGLRenderInterface.cpp index e1271ce45dcba..e6978918f0b15 100644 --- a/dart/renderer/OpenGLRenderInterface.cpp +++ b/dart/renderer/OpenGLRenderInterface.cpp @@ -421,26 +421,35 @@ void OpenGLRenderInterface::drawList(GLuint index) { glCallList(index); } +void OpenGLRenderInterface::drawLineSegments( + const std::vector& _vertices, + const Eigen::aligned_vector& _connections) +{ + glBegin(GL_LINES); + for(const Eigen::Vector2i& c : _connections) + { + const Eigen::Vector3d& v1 = _vertices[c[0]]; + const Eigen::Vector3d& v2 = _vertices[c[1]]; + glVertex3f(v1[0], v1[1], v1[2]); + glVertex3f(v2[0], v2[1], v2[2]); + } + glEnd(); +} + //============================================================================== void OpenGLRenderInterface::compileList(dynamics::Skeleton* _skel) { - DART_SUPPRESS_DEPRECATED_BEGIN - - if(_skel == 0) - return; + if(_skel == 0) + return; for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) { compileList(_skel->getBodyNode(i)); } - - DART_SUPPRESS_DEPRECATED_END } //============================================================================== void OpenGLRenderInterface::compileList(dynamics::BodyNode* node) { - DART_SUPPRESS_DEPRECATED_BEGIN - if(node == 0) return; @@ -456,8 +465,6 @@ void OpenGLRenderInterface::compileList(dynamics::BodyNode* node) auto shapeNode = node->getNode(i); compileList(shapeNode->getShape().get()); } - - DART_SUPPRESS_DEPRECATED_END } //============================================================================== @@ -512,249 +519,6 @@ GLuint OpenGLRenderInterface::compileList(const Eigen::Vector3d& _scale, const a return index; } -//============================================================================== -void OpenGLRenderInterface::draw(dynamics::Skeleton* _skel, bool _vizCol, - bool _colMesh) -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if(_skel == 0) - return; - - for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) - draw(_skel->getBodyNode(i), _vizCol, _colMesh); - - DART_SUPPRESS_DEPRECATED_END -} - -//============================================================================== -void OpenGLRenderInterface::draw(dynamics::BodyNode* node, - bool vizCol, bool colMesh) -{ - DART_SUPPRESS_DEPRECATED_BEGIN - - if(node == 0) - return; - - // Get world transform - Eigen::Isometry3d pose; - pose = node->getTransform(); - - // GL calls - if(vizCol && node->isColliding()) - { - glDisable(GL_TEXTURE_2D); - glEnable(GL_COLOR_MATERIAL); - glColor3f(1.0f, .1f, .1f); - } - - glPushMatrix(); - glMultMatrixd(pose.data()); - - for (auto childFrame : node->getChildFrames()) - { - auto shapeFrame = dynamic_cast(childFrame); - - if (!shapeFrame) - continue; - - if (shapeFrame->hasVisualAddon()) - draw(shapeFrame->getShape().get()); - else if (colMesh && shapeFrame->hasCollisionAddon()) - draw(shapeFrame->getShape().get()); - } - - for (auto i = 0u; i < node->getNumNodes(); ++i) - { - auto shapeNode = node->getNode(i); - if (shapeNode->hasVisualAddon()) - draw(shapeNode->getShape().get()); - else if (colMesh && shapeNode->hasCollisionAddon()) - draw(shapeNode->getShape().get()); - } - - glColor3f(1.0f,1.0f,1.0f); - glEnable( GL_TEXTURE_2D ); - glDisable(GL_COLOR_MATERIAL); - glPopMatrix(); - - DART_SUPPRESS_DEPRECATED_END -} - -//============================================================================== -void OpenGLRenderInterface::draw(dynamics::Shape* shape) -{ - //FIXME: Refactor this to use polymorphism. - - if(nullptr == shape) - return; - - glPushMatrix(); - - glColorMaterial ( GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE ); - glEnable ( GL_COLOR_MATERIAL ); - - switch(shape->getShapeType()) - { - case dynamics::Shape::BOX: - { - //FIXME: We are not in a glut instance - dynamics::BoxShape* box = static_cast(shape); - drawCube(box->getSize()); - break; - } - case dynamics::Shape::CYLINDER: - { - //FIXME: We are not in a glut instance - dynamics::CylinderShape* cylinder = static_cast(shape); - drawCylinder(cylinder->getRadius(), cylinder->getHeight()); - break; - } - case dynamics::Shape::ELLIPSOID: - { - //FIXME: We are not in a glut instance - dynamics::EllipsoidShape* ellipsoid = static_cast(shape); - drawEllipsoid(ellipsoid->getSize()); - break; - } - case dynamics::Shape::PLANE: - { - dterr << "PLANE shape is not supported yet." << std::endl; - break; - } - case dynamics::Shape::MESH: - { - glDisable(GL_COLOR_MATERIAL); // Use mesh colors to draw - - dynamics::MeshShape* mesh = static_cast(shape); - - if(!mesh) - break; - else if(mesh->getDisplayList()) - drawList(mesh->getDisplayList()); - else - drawMesh(mesh->getScale(), mesh->getMesh()); - - break; - } - case dynamics::Shape::SOFT_MESH: - { - // Do nothing - break; - } - case dynamics::Shape::LINE_SEGMENT: - { - dynamics::LineSegmentShape* lineSegments = - static_cast(shape); - drawLineSegments(lineSegments->getVertices(), - lineSegments->getConnections()); - } - } - - glDisable(GL_COLOR_MATERIAL); - glPopMatrix(); -} - -//============================================================================== -void OpenGLRenderInterface::draw(dynamics::ShapeFrame* shapeFrame) -{ - if(nullptr == shapeFrame) - return; - - auto shape = shapeFrame->getShape().get(); - - Eigen::Isometry3d pose = shapeFrame->getRelativeTransform(); - auto visualAddon = shapeFrame->get(); - - Eigen::Vector3d color = Eigen::Vector3d::Random(); - if (visualAddon) - color = visualAddon->getColor(); - - glPushMatrix(); - - glColorMaterial ( GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE ); - glEnable ( GL_COLOR_MATERIAL ); - - glColor3d(color[0], color[1], color[2]); - - glMultMatrixd(pose.data()); - - switch(shape->getShapeType()) - { - case dynamics::Shape::BOX: - { - //FIXME: We are not in a glut instance - dynamics::BoxShape* box = static_cast(shape); - drawCube(box->getSize()); - break; - } - case dynamics::Shape::CYLINDER: - { - //FIXME: We are not in a glut instance - dynamics::CylinderShape* cylinder = static_cast(shape); - drawCylinder(cylinder->getRadius(), cylinder->getHeight()); - break; - } - case dynamics::Shape::ELLIPSOID: - { - //FIXME: We are not in a glut instance - dynamics::EllipsoidShape* ellipsoid = static_cast(shape); - drawEllipsoid(ellipsoid->getSize()); - break; - } - case dynamics::Shape::PLANE: - { - dterr << "PLANE shape is not supported yet." << std::endl; - break; - } - case dynamics::Shape::MESH: - { - glDisable(GL_COLOR_MATERIAL); // Use mesh colors to draw - - dynamics::MeshShape* mesh = static_cast(shape); - - if(!mesh) - break; - else if(mesh->getDisplayList()) - drawList(mesh->getDisplayList()); - else - drawMesh(mesh->getScale(), mesh->getMesh()); - - break; - } - case dynamics::Shape::SOFT_MESH: - { - // Do nothing - break; - } - case dynamics::Shape::LINE_SEGMENT: - { - dynamics::LineSegmentShape* lineSegments = - static_cast(shape); - drawLineSegments(lineSegments->getVertices(), - lineSegments->getConnections()); - } - } - - glDisable(GL_COLOR_MATERIAL); - glPopMatrix(); -} - -void OpenGLRenderInterface::drawLineSegments( - const std::vector& _vertices, - const Eigen::aligned_vector& _connections) -{ - glBegin(GL_LINES); - for(const Eigen::Vector2i& c : _connections) - { - const Eigen::Vector3d& v1 = _vertices[c[0]]; - const Eigen::Vector3d& v2 = _vertices[c[1]]; - glVertex3f(v1[0], v1[1], v1[2]); - glVertex3f(v2[0], v2[1], v2[2]); - } - glEnd(); -} - void OpenGLRenderInterface::setPenColor(const Eigen::Vector4d& _col) { glColor4d(_col[0], _col[1], _col[2], _col[3]); } diff --git a/dart/renderer/OpenGLRenderInterface.h b/dart/renderer/OpenGLRenderInterface.h index 0255ec964d294..37035c7db9600 100644 --- a/dart/renderer/OpenGLRenderInterface.h +++ b/dart/renderer/OpenGLRenderInterface.h @@ -81,16 +81,11 @@ class OpenGLRenderInterface : public RenderInterface { virtual void transform(const Eigen::Isometry3d& _transform) override; //glMultMatrix virtual void scale(const Eigen::Vector3d& _scale) override; //glScale - DEPRECATED(6.0) void compileList(dynamics::Skeleton* _skel); - DEPRECATED(6.0) void compileList(dynamics::BodyNode* _node); - DEPRECATED(6.0) void compileList(dynamics::Shape* _shape); + void compileList(dynamics::Skeleton* _skel); + void compileList(dynamics::BodyNode* _node); + void compileList(dynamics::Shape* _shape); GLuint compileList(const Eigen::Vector3d& _scale, const aiScene* _mesh); - DEPRECATED(6.0) virtual void draw(dynamics::Skeleton* _skel, bool _vizCol = false, bool _colMesh = false); - DEPRECATED(6.0) virtual void draw(dynamics::BodyNode* _node, bool _vizCol = false, bool _colMesh = false); - DEPRECATED(6.0) virtual void draw(dynamics::Shape* _shape); - DEPRECATED(6.0) virtual void draw(dynamics::ShapeFrame* shapeFrame); - virtual void drawEllipsoid(const Eigen::Vector3d& _size) override; virtual void drawCube(const Eigen::Vector3d& _size) override; virtual void drawCylinder(double _radius, double _height) override;